diff --git a/.gitignore b/.gitignore index e414e4301a..3e91531d08 100644 --- a/.gitignore +++ b/.gitignore @@ -46,7 +46,6 @@ selfdrive/boardd/boardd selfdrive/logcatd/logcatd selfdrive/mapd/default_speeds_by_region.json system/proclogd/proclogd -selfdrive/ui/_ui selfdrive/ui/translations/alerts_generated.h selfdrive/ui/translations/tmp selfdrive/test/longitudinal_maneuvers/out diff --git a/Jenkinsfile b/Jenkinsfile index 1e1d485b10..d716510bfe 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,10 +1,23 @@ +def retryWithDelay(int maxRetries, int delay, Closure body) { + for (int i = 0; i < maxRetries; i++) { + try { + return body() + } catch (Exception e) { + sleep(delay) + } + } + throw Exception("Failed after ${maxRetries} retries") +} + def device(String ip, String step_label, String cmd) { withCredentials([file(credentialsId: 'id_rsa', variable: 'key_file')]) { def ssh_cmd = """ -ssh -tt -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'END' +ssh -tt -o ConnectTimeout=5 -o ServerAliveInterval=5 -o ServerAliveCountMax=2 -o BatchMode=yes -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'END' set -e +shopt -s huponexit # kill all child processes when the shell exits + export CI=1 export PYTHONWARNINGS=error export LOGPRINT=debug @@ -14,7 +27,8 @@ export GIT_BRANCH=${env.GIT_BRANCH} export GIT_COMMIT=${env.GIT_COMMIT} export AZURE_TOKEN='${env.AZURE_TOKEN}' export MAPBOX_TOKEN='${env.MAPBOX_TOKEN}' -export PYTEST_ADDOPTS="-c selfdrive/test/pytest-tici.ini --rootdir ." +# only use 1 thread for tici tests since most require HIL +export PYTEST_ADDOPTS="-n 0" export GIT_SSH_COMMAND="ssh -i /data/gitkey" @@ -23,7 +37,9 @@ source ~/.bash_profile if [ -f /TICI ]; then source /etc/profile + rm -rf /tmp/tmp* rm -rf ~/.commacache + rm -rf /dev/shm/* if ! systemctl is-active --quiet systemd-resolved; then echo "restarting resolved" @@ -55,16 +71,17 @@ END""" } } -def deviceStage(String stageName, String deviceType, List env, def steps) { +def deviceStage(String stageName, String deviceType, List extra_env, def steps) { stage(stageName) { if (currentBuild.result != null) { return } - def extra = env.collect { "export ${it}" }.join('\n'); + def extra = extra_env.collect { "export ${it}" }.join('\n'); + def branch = env.BRANCH_NAME ?: 'master'; - docker.image('ghcr.io/commaai/alpine-ssh').inside('--user=root') { - lock(resource: "", label: deviceType, inversePrecedence: true, variable: 'device_ip', quantity: 1) { + lock(resource: "", label: deviceType, inversePrecedence: true, variable: 'device_ip', quantity: 1, resourceSelectStrategy: 'random') { + docker.image('ghcr.io/commaai/alpine-ssh').inside('--user=root') { timeout(time: 20, unit: 'MINUTES') { retry (3) { device(device_ip, "git checkout", extra + "\n" + readFile("selfdrive/test/setup_device_ci.sh")) @@ -87,26 +104,31 @@ def pcStage(String stageName, Closure body) { checkout scm - def dockerArgs = "--user=batman -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/scons_cache:/tmp/scons_cache -e PYTHONPATH=${env.WORKSPACE}"; - docker.build("openpilot-base:build-${env.GIT_COMMIT}", "-f Dockerfile.openpilot_base .").inside(dockerArgs) { - timeout(time: 20, unit: 'MINUTES') { - try { - // TODO: remove these after all jenkins jobs are running as batman (merged with master) - sh "sudo chown -R batman:batman /tmp/scons_cache" - sh "sudo chown -R batman:batman /tmp/comma_download_cache" - - sh "git config --global --add safe.directory '*'" - sh "git submodule update --init --recursive" - sh "git lfs pull" - body() - } finally { - sh "rm -rf ${env.WORKSPACE}/* || true" - sh "rm -rf .* || true" + def dockerArgs = "--user=batman -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/scons_cache:/tmp/scons_cache -e PYTHONPATH=${env.WORKSPACE} --cpus=8 --memory 16g -e PYTEST_ADDOPTS='-n8'"; + + def openpilot_base = retryWithDelay (3, 15) { + return docker.build("openpilot-base:build-${env.GIT_COMMIT}", "-f Dockerfile.openpilot_base .") + } + + lock(resource: "", label: 'pc', inversePrecedence: true, quantity: 1) { + openpilot_base.inside(dockerArgs) { + timeout(time: 20, unit: 'MINUTES') { + try { + retryWithDelay (3, 15) { + sh "git config --global --add safe.directory '*'" + sh "git submodule update --init --recursive" + sh "git lfs pull" + } + body() + } finally { + sh "rm -rf ${env.WORKSPACE}/* || true" + sh "rm -rf .* || true" + } + } } } } } - } } def setupCredentials() { @@ -119,6 +141,7 @@ def setupCredentials() { } } + node { env.CI = "1" env.PYTHONWARNINGS = "error" @@ -130,7 +153,7 @@ node { env.GIT_COMMIT = checkout(scm).GIT_COMMIT def excludeBranches = ['master-ci', 'devel', 'devel-staging', 'release3', 'release3-staging', - 'dashcam3', 'dashcam3-staging', 'testing-closet*', 'hotfix-*'] + 'testing-closet*', 'hotfix-*'] def excludeRegex = excludeBranches.join('|').replaceAll('\\*', '.*') if (env.BRANCH_NAME != 'master') { @@ -142,7 +165,7 @@ node { try { if (env.BRANCH_NAME == 'devel-staging') { deviceStage("build release3-staging", "tici-needs-can", [], [ - ["build release3-staging & dashcam3-staging", "RELEASE_BRANCH=release3-staging DASHCAM_BRANCH=dashcam3-staging $SOURCE_DIR/release/build_release.sh"], + ["build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"], ]) } @@ -156,8 +179,9 @@ node { parallel ( // tici tests 'onroad tests': { - deviceStage("onroad", "tici-needs-can", ["SKIP_COPY=1"], [ - ["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR ./build_devel.sh"], + deviceStage("onroad", "tici-needs-can", [], [ + // TODO: ideally, this test runs in master-ci, but it takes 5+m to build it + //["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR $SOURCE_DIR/scripts/retry.sh ./build_devel.sh"], ["build openpilot", "cd selfdrive/manager && ./build.py"], ["check dirty", "release/check-dirty.sh"], ["onroad tests", "pytest selfdrive/test/test_onroad.py -s"], @@ -165,18 +189,17 @@ node { ]) }, 'HW + Unit Tests': { - deviceStage("tici", "tici-common", ["UNSAFE=1"], [ + deviceStage("tici-hardware", "tici-common", ["UNSAFE=1"], [ ["build", "cd selfdrive/manager && ./build.py"], ["test pandad", "pytest selfdrive/boardd/tests/test_pandad.py"], - ["test power draw", "./system/hardware/tici/tests/test_power_draw.py"], + ["test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"], ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py"], ["test pigeond", "pytest system/sensord/tests/test_pigeond.py"], ["test manager", "pytest selfdrive/manager/test/test_manager.py"], - ["test nav", "pytest selfdrive/navd/tests/"], ]) }, 'loopback': { - deviceStage("tici", "tici-loopback", ["UNSAFE=1"], [ + deviceStage("loopback", "tici-loopback", ["UNSAFE=1"], [ ["build openpilot", "cd selfdrive/manager && ./build.py"], ["test boardd loopback", "pytest selfdrive/boardd/tests/test_boardd_loopback.py"], ]) @@ -204,7 +227,7 @@ node { ]) }, 'replay': { - deviceStage("tici", "tici-replay", ["UNSAFE=1"], [ + deviceStage("model-replay", "tici-replay", ["UNSAFE=1"], [ ["build", "cd selfdrive/manager && ./build.py"], ["model replay", "selfdrive/test/process_replay/model_replay.py"], ]) @@ -216,27 +239,10 @@ node { ["test pandad", "pytest selfdrive/boardd/tests/test_pandad.py"], ["test amp", "pytest system/hardware/tici/tests/test_amplifier.py"], ["test hw", "pytest system/hardware/tici/tests/test_hardware.py"], - ["test rawgpsd", "pytest system/sensord/rawgps/test_rawgps.py"], + ["test qcomgpsd", "pytest system/qcomgpsd/tests/test_qcomgpsd.py"], ]) }, - // *** PC tests *** - 'PC tests': { - pcStage("PC tests") { - // tests that our build system's dependencies are configured properly, - // needs a machine with lots of cores - sh label: "test multi-threaded build", script: "scons --no-cache --random -j42" - } - }, - 'car tests': { - pcStage("car tests") { - sh label: "build", script: "selfdrive/manager/build.py" - sh label: "test_models.py", script: "INTERNAL_SEG_CNT=250 INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt FILEREADER_CACHE=1 \ - pytest -n42 --dist=loadscope selfdrive/car/tests/test_models.py" - sh label: "test_car_interfaces.py", script: "MAX_EXAMPLES=100 pytest -n42 --dist=load selfdrive/car/tests/test_car_interfaces.py" - } - }, - ) } } catch (Exception e) { diff --git a/README.md b/README.md index 7d051ada14..db74ee6a1a 100644 --- a/README.md +++ b/README.md @@ -1,18 +1,4 @@ -![openpilot on the comma 3X](https://github.com/commaai/openpilot/assets/4038174/f1081737-8718-4241-a22a-3ceba526361a) - -Table of Contents -======================= - -* [What is openpilot?](#what-is-openpilot) -* [Running in a car](#running-on-a-dedicated-device-in-a-car) -* [Running on PC](#running-on-pc) -* [Community and Contributing](#community-and-contributing) -* [User Data and comma Account](#user-data-and-comma-account) -* [Safety and Testing](#safety-and-testing) -* [Directory Structure](#directory-structure) -* [Licensing](#licensing) - ---- +[![openpilot on the comma 3X](https://github.com/commaai/openpilot/assets/8762862/f09e6d29-db2d-4179-80c2-51e8d92bdb5c)](https://comma.ai/shop/comma-3x) What is openpilot? ------ @@ -21,59 +7,47 @@ What is openpilot? - - - - - - - - - - + + +
- -Running on a dedicated device in a car +To start using openpilot in a car ------ -To use openpilot in a car, you need four things -1. **Supported Device:** A comma 3/3X. You can purchase these devices from (https://comma.ai/shop/comma-3x) - -2. **Software:** The setup procedure for the comma 3/3X allows users to enter a URL for custom software. - To install the release version of openpilot, use the URL `openpilot.comma.ai`. - To install openpilot master (for more advanced users), use the URL `installer.comma.ai/commaai/master`. You can replace "commaai" with another GitHub username to install a fork. - -3. **Supported Car:** Ensure that you have one of [the 250+ supported cars](docs/CARS.md). openpilot supports a wide range of car makes including Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, Ford, and many more. - If your car is not officially listed as supported but has adaptive cruise control and lane-keeping assist, it's likely capable of running openpilot. - +To use openpilot in a car, you need four things: +1. **Supported Device:** a comma 3/3X, available at [comma.ai/shop](https://comma.ai/shop/comma-3x). +2. **Software:** The setup procedure for the comma 3/3X allows users to enter a URL for custom software. Use the URL `openpilot.comma.ai` to install the release version. +3. **Supported Car:** Ensure that you have one of [the 250+ supported cars](docs/CARS.md). 4. **Car Harness:** You will also need a [car harness](https://comma.ai/shop/car-harness) to connect your comma 3/3X to your car. - We have detailed instructions for [how to install the harness and device in a car](https://comma.ai/setup). -Running on PC ------- +We have detailed instructions for [how to install the harness and device in a car](https://comma.ai/setup). Note that it's possible to run openpilot on [other hardware](https://blog.comma.ai/self-driving-car-for-free/), although it's not plug-and-play. -All openpilot services can run as usual on a PC without requiring special hardware or a car. You can also run openpilot on recorded or simulated data to develop or experiment with openpilot. - -With openpilot's tools, you can plot logs, replay drives, and watch the full-res camera streams. See [the tools README](tools/README.md) for more information. - -You can also run openpilot in simulation [with the CARLA simulator](tools/sim/README.md). This allows openpilot to drive around a virtual car on your Ubuntu machine. The whole setup should only take a few minutes but does require a decent GPU. - -A PC running openpilot can also control your vehicle if it is connected to a [webcam](https://github.com/commaai/openpilot/tree/master/tools/webcam), a [black panda](https://comma.ai/shop/products/panda), and a [harness](https://comma.ai/shop/products/car-harness). - -Community and Contributing +To start developing openpilot ------ -openpilot is developed by [comma](https://comma.ai/) and by users like you. We welcome both pull requests and issues on [GitHub](http://github.com/commaai/openpilot). Bug fixes and new car ports are encouraged. Check out [the contributing docs](docs/CONTRIBUTING.md). +openpilot is developed by [comma](https://comma.ai/) and by users like you. We welcome both pull requests and issues on [GitHub](http://github.com/commaai/openpilot). -Documentation related to openpilot development can be found on [docs.comma.ai](https://docs.comma.ai). Information about running openpilot (e.g. FAQ, fingerprinting, troubleshooting, custom forks, community hardware) should go on the [wiki](https://github.com/commaai/openpilot/wiki). +* Join the [community Discord](https://discord.comma.ai) +* Check out [the contributing docs](docs/CONTRIBUTING.md) +* Check out the [openpilot tools](tools/) +* Read about the [development workflow](docs/WORKFLOW.md) +* Code documentation lives at https://docs.comma.ai +* Information about running openpilot lives on the [community wiki](https://github.com/commaai/openpilot/wiki) -You can add support for your car by following guides we have written for [Brand](https://blog.comma.ai/how-to-write-a-car-port-for-openpilot/) and [Model](https://blog.comma.ai/openpilot-port-guide-for-toyota-models/) ports. Generally, a car with adaptive cruise control and lane keep assist is a good candidate. [Join our Discord](https://discord.comma.ai) to discuss car ports: most car makes have a dedicated channel. +Want to get paid to work on openpilot? [comma is hiring](https://comma.ai/jobs#open-positions) and offers lots of [bounties](docs/BOUNTIES.md) for external contributors. -Want to get paid to work on openpilot? [comma is hiring](https://comma.ai/jobs#open-positions). +Safety and Testing +---- -And [follow us on Twitter](https://twitter.com/comma_ai). +* openpilot observes [ISO26262](https://en.wikipedia.org/wiki/ISO_26262) guidelines, see [SAFETY.md](docs/SAFETY.md) for more details. +* openpilot has software-in-the-loop [tests](.github/workflows/selfdrive_tests.yaml) that run on every commit. +* The code enforcing the safety model lives in panda and is written in C, see [code rigor](https://github.com/commaai/panda#code-rigor) for more details. +* panda has software-in-the-loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). +* Internally, we have a hardware-in-the-loop Jenkins test suite that builds and unit tests the various processes. +* panda has additional hardware-in-the-loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). +* We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes. User Data and comma Account ------ @@ -87,49 +61,6 @@ The driver-facing camera is only logged if you explicitly opt-in in settings. Th By using openpilot, you agree to [our Privacy Policy](https://comma.ai/privacy). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma for the use of this data. -Safety and Testing ----- - -* openpilot observes ISO26262 guidelines, see [SAFETY.md](docs/SAFETY.md) for more details. -* openpilot has software-in-the-loop [tests](.github/workflows/selfdrive_tests.yaml) that run on every commit. -* The code enforcing the safety model lives in panda and is written in C, see [code rigor](https://github.com/commaai/panda#code-rigor) for more details. -* panda has software-in-the-loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). -* Internally, we have a hardware-in-the-loop Jenkins test suite that builds and unit tests the various processes. -* panda has additional hardware-in-the-loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). -* We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes. - -Directory Structure ------- - . - ├── cereal # The messaging spec and libs used for all logs - ├── common # Library like functionality we've developed here - ├── docs # Documentation - ├── opendbc # Files showing how to interpret data from cars - ├── panda # Code used to communicate on CAN - ├── third_party # External libraries - └── system # Generic services - ├── camerad # Driver to capture images from the camera sensors - ├── hardware # Hardware abstraction classes - ├── logcatd # systemd journal as a service - ├── loggerd # Logger and uploader of car data - ├── proclogd # Logs information from /proc - ├── sensord # IMU interface code - └── ubloxd # u-blox GNSS module interface code - └── selfdrive # Code needed to drive the car - ├── assets # Fonts, images, and sounds for UI - ├── athena # Allows communication with the app - ├── boardd # Daemon to talk to the board - ├── car # Car specific code to read states and control actuators - ├── controls # Planning and controls - ├── debug # Tools to help you debug and do car ports - ├── locationd # Precise localization and vehicle parameter estimation - ├── manager # Daemon that starts/stops all other daemons as needed - ├── modeld # Driving and monitoring model runners - ├── monitoring # Daemon to determine driver attention - ├── navd # Turn-by-turn navigation - ├── test # Unit tests, system tests, and a car simulator - └── ui # The UI - Licensing ------ @@ -145,5 +76,5 @@ NO WARRANTY EXPRESSED OR IMPLIED.** -[![openpilot tests](https://github.com/commaai/openpilot/workflows/openpilot%20tests/badge.svg?event=push)](https://github.com/commaai/openpilot/actions) +![openpilot tests](https://github.com/commaai/openpilot/actions/workflows/selfdrive_tests.yaml/badge.svg) [![codecov](https://codecov.io/gh/commaai/openpilot/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/openpilot) diff --git a/RELEASES.md b/RELEASES.md index 1cb6105680..0a866008df 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,23 @@ +Version 0.9.6 (2024-02-27) +======================== +* New driving model + * Vision model trained on more data + * Improved driving performance + * Directly outputs curvature for lateral control +* New driver monitoring model + * Trained on larger dataset +* AGNOS 9 +* comma body streaming and controls over WebRTC +* Improved fuzzy fingerprinting for many makes and models +* Alpha longitudinal support for new Toyota models +* Chevrolet Equinox 2019-22 support thanks to JasonJShuler and nworb-cire! +* Dodge Durango 2020-21 support +* Hyundai Staria 2023 support thanks to sunnyhaibin! +* Kia Niro Plug-in Hybrid 2022 support thanks to sunnyhaibin! +* Lexus LC 2024 support thanks to nelsonjchen! +* Toyota RAV4 2023-24 support +* Toyota RAV4 Hybrid 2023-24 support + Version 0.9.5 (2023-11-17) ======================== * New driving model diff --git a/SConstruct b/SConstruct index eb9cd737e2..b04e3903ed 100644 --- a/SConstruct +++ b/SConstruct @@ -9,11 +9,16 @@ import SCons.Errors SCons.Warnings.warningAsException(True) +# pending upstream fix - https://github.com/SCons/scons/issues/4461 +#SetOption('warn', 'all') + TICI = os.path.isfile('/TICI') AGNOS = TICI Decider('MD5-timestamp') +SetOption('num_jobs', int(os.cpu_count()/2)) + AddOption('--kaitai', action='store_true', help='Regenerate kaitai struct parsers') @@ -37,7 +42,7 @@ AddOption('--clazy', AddOption('--compile_db', action='store_true', help='build clang compilation database') - + AddOption('--ccflags', action='store', type='string', @@ -116,10 +121,7 @@ else: cflags = [] cxxflags = [] cpppath = [] - rpath += [ - Dir("#cereal").abspath, - Dir("#common").abspath - ] + rpath += [] # MacOS if arch == "Darwin": @@ -143,9 +145,6 @@ else: libpath = [ f"#third_party/acados/{arch}/lib", f"#third_party/libyuv/{arch}/lib", - f"#third_party/mapbox-gl-native-qt/{arch}", - "#cereal", - "#common", "/usr/lib", "/usr/local/lib", ] @@ -208,11 +207,12 @@ env = Environment( "#third_party/json11", "#third_party/linux/include", "#third_party/snpe/include", - "#third_party/mapbox-gl-native-qt/include", "#third_party/qrcode", "#third_party", "#cereal", "#opendbc/can", + "#third_party/maplibre-native-qt/include", + f"#third_party/maplibre-native-qt/{arch}/include" ], CC='clang', @@ -229,10 +229,13 @@ env = Environment( "#opendbc/can", "#selfdrive/boardd", "#common", + "#rednose/helpers", ], CYTHONCFILESUFFIX=".cpp", COMPILATIONDB_USE_ABSPATH=True, - tools=["default", "cython", "compilation_db"], + REDNOSE_ROOT="#", + tools=["default", "cython", "compilation_db", "rednose_filter"], + toolpath=["#rednose_repo/site_scons/site_tools"], ) if arch == "Darwin": @@ -294,8 +297,11 @@ else: qt_env['QTDIR'] = qt_install_prefix qt_dirs = [ f"{qt_install_headers}", - f"{qt_install_headers}/QtGui/5.12.8/QtGui", ] + + qt_gui_path = os.path.join(qt_install_headers, "QtGui") + qt_gui_dirs = [d for d in os.listdir(qt_gui_path) if os.path.isdir(os.path.join(qt_gui_path, d))] + qt_dirs += [f"{qt_install_headers}/QtGui/{qt_gui_dirs[0]}/QtGui", ] if qt_gui_dirs else [] qt_dirs += [f"{qt_install_headers}/Qt{m}" for m in qt_modules] qt_libs = [f"Qt5{m}" for m in qt_modules] @@ -312,7 +318,7 @@ try: except SCons.Errors.UserError: qt_env.Tool('qt') -qt_env['CPPPATH'] += qt_dirs + ["#selfdrive/ui/qt/"] +qt_env['CPPPATH'] += qt_dirs# + ["#selfdrive/ui/qt/"] qt_flags = [ "-D_REENTRANT", "-DQT_NO_DEBUG", @@ -325,7 +331,8 @@ qt_flags = [ "-DQT_MESSAGELOGCONTEXT", ] qt_env['CXXFLAGS'] += qt_flags -qt_env['LIBPATH'] += ['#selfdrive/ui'] +qt_env['LIBPATH'] += ['#selfdrive/ui', f"#third_party/maplibre-native-qt/{arch}/lib"] +qt_env['RPATH'] += [Dir(f"#third_party/maplibre-native-qt/{arch}/lib").srcnode().abspath] qt_env['LIBS'] = qt_libs if GetOption("clazy"): @@ -367,31 +374,7 @@ SConscript([ 'panda/SConscript', ]) -# Build rednose library and ekf models -rednose_deps = [ - "#selfdrive/locationd/models/constants.py", - "#selfdrive/locationd/models/gnss_helpers.py", -] - -rednose_config = { - 'generated_folder': '#selfdrive/locationd/models/generated', - 'to_build': { - 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, [], rednose_deps), - 'live': ('#selfdrive/locationd/models/live_kf.py', True, ['live_kf_constants.h'], rednose_deps), - 'car': ('#selfdrive/locationd/models/car_kf.py', True, [], rednose_deps), - }, -} - -if arch != "larch64": - rednose_config['to_build'].update({ - 'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, [], rednose_deps), - 'lane': ('#selfdrive/locationd/models/lane_kf.py', True, [], rednose_deps), - 'pos_computer_4': ('#rednose/helpers/lst_sq_computer.py', False, [], []), - 'pos_computer_5': ('#rednose/helpers/lst_sq_computer.py', False, [], []), - 'feature_handler_5': ('#rednose/helpers/feature_handler.py', False, [], []), - }) - -Export('rednose_config') +# Build rednose library SConscript(['rednose/SConscript']) # Build system services diff --git a/body/board/SConscript b/body/board/SConscript index f4a532a17f..39927c8be1 100644 --- a/body/board/SConscript +++ b/body/board/SConscript @@ -31,7 +31,7 @@ if os.getenv("RELEASE"): assert os.path.exists(cert_fn), 'Certificate file not found. Please specify absolute path' else: BUILD_TYPE = "DEBUG" - cert_fn = File("../certs/debug").srcnode().abspath + cert_fn = File("../certs/debug").srcnode().relpath common_flags += ["-DALLOW_DEBUG"] if os.getenv("DEBUG"): @@ -99,7 +99,7 @@ def to_c_uint32(x): def get_key_header(name): from Crypto.PublicKey import RSA - public_fn = File(f'../certs/{name}.pub').srcnode().abspath + public_fn = f'../certs/{name}.pub' rsa = RSA.importKey(open(public_fn).read()) assert(rsa.size_in_bits() == 1024) @@ -132,7 +132,7 @@ with open("obj/cert.h", "w") as f: for project_name in build_projects: project = build_projects[project_name] - linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().abspath + linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().relpath flags = [ "-Wall", @@ -193,5 +193,5 @@ for project_name in build_projects: main_bin = project_env.Objcopy(f"obj/{project_name}.bin", main_elf) # Sign main - sign_py = File("../crypto/sign.py").srcnode().abspath + sign_py = File("../crypto/sign.py").srcnode().relpath panda_bin_signed = project_env.Command(f"obj/{project_name}.bin.signed", main_bin, f"SETLEN=1 {sign_py} $SOURCE $TARGET {cert_fn}") diff --git a/body/board/inc/stm32f4xx.h b/body/board/inc/stm32f4xx.h index 35ec65a6da..79d83bf4ee 100644 --- a/body/board/inc/stm32f4xx.h +++ b/body/board/inc/stm32f4xx.h @@ -8,8 +8,8 @@ * is using in the C source code, usually in main.c. This file contains: * - Configuration section that allows to select: * - The STM32F4xx device used in the target application - * - To use or not the peripherals drivers in application code(i.e. - * code will be based on direct access to peripherals registers + * - To use or not the peripheral's drivers in application code(i.e. + * code will be based on direct access to peripheral's registers * rather than drivers API), this option is controlled by * "#define USE_HAL_DRIVER" * diff --git a/cereal/__init__.py b/cereal/__init__.py index 4e26ffb2ed..89c5cf38e3 100644 --- a/cereal/__init__.py +++ b/cereal/__init__.py @@ -1,4 +1,3 @@ -# pylint: skip-file import os import capnp diff --git a/cereal/car.capnp b/cereal/car.capnp index 29949a1480..3d7d737dcd 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -51,7 +51,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { parkBrake @29; manualRestart @30; lowSpeedLockout @31; - plannerError @32; joystickDebug @34; steerTempUnavailableSilent @35; resumeRequired @36; @@ -142,6 +141,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { startupFuzzyFingerprintDEPRECATED @97; noTargetDEPRECATED @25; brakeUnavailableDEPRECATED @2; + plannerErrorDEPRECATED @32; } } @@ -484,6 +484,7 @@ struct CarParams { openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control? carVin @38 :Text; # VIN number queried during fingerprinting dashcamOnly @41: Bool; + passive @73: Bool; # is openpilot in control? transmissionType @43 :TransmissionType; carFw @44 :List(CarFw); @@ -595,12 +596,14 @@ struct CarParams { body @27; hyundaiCanfd @28; volkswagenMqbEvo @29; + chryslerCusw @30; } enum SteerControlType { torque @0; angle @1; - curvature @2; + + curvatureDEPRECATED @2; } enum TransmissionType { diff --git a/cereal/log.capnp b/cereal/log.capnp index 12e25b14f3..9f0ca64f8b 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -33,6 +33,7 @@ struct InitData { deviceType @3 :DeviceType; version @4 :Text; gitCommit @10 :Text; + gitCommitDate @21 :Text; gitBranch @11 :Text; gitRemote @13 :Text; @@ -130,8 +131,9 @@ struct InitData { struct FrameData { frameId @0 :UInt32; - encodeId @1 :UInt32; # DEPRECATED frameIdSensor @25 :UInt32; + requestId @28 :UInt32; + encodeId @1 :UInt32; frameType @7 :FrameType; @@ -166,6 +168,7 @@ struct FrameData { unknown @0; ar0231 @1; ox03c10 @2; + os04c10 @3; } frameLengthDEPRECATED @3 :Int32; @@ -297,6 +300,29 @@ struct GpsLocationData { } } +enum Desire { + none @0; + turnLeft @1; + turnRight @2; + laneChangeLeft @3; + laneChangeRight @4; + keepLeft @5; + keepRight @6; +} + +enum LaneChangeState { + off @0; + preLaneChange @1; + laneChangeStarting @2; + laneChangeFinishing @3; +} + +enum LaneChangeDirection { + none @0; + left @1; + right @2; +} + struct CanData { address @0 :UInt32; busTime @1 :UInt16; @@ -331,7 +357,6 @@ struct DeviceState @0xa4d8b5af2aa492eb { cpuTempC @26 :List(Float32); gpuTempC @27 :List(Float32); memoryTempC @28 :Float32; - ambientTempC @30 :Float32; nvmeTempC @35 :List(Float32); modemTempC @36 :List(Float32); pmicTempC @39 :List(Float32); @@ -404,11 +429,11 @@ struct DeviceState @0xa4d8b5af2aa492eb { chargingErrorDEPRECATED @17 :Bool; chargingDisabledDEPRECATED @18 :Bool; usbOnlineDEPRECATED @12 :Bool; + ambientTempCDEPRECATED @30 :Float32; } struct PandaState @0xa7649e2575e4591e { ignitionLine @2 :Bool; - gasInterceptorDetected @4 :Bool; rxBufferOverflow @7 :UInt32; txBufferOverflow @8 :UInt32; gmlanSendErrs @9 :UInt32; @@ -494,6 +519,7 @@ struct PandaState @0xa7649e2575e4591e { redPanda @7; redPandaV2 @8; tres @9; + cuatro @10; } enum HarnessStatus { @@ -541,6 +567,7 @@ struct PandaState @0xa7649e2575e4591e { } } + gasInterceptorDetectedDEPRECATED @4 :Bool; startedSignalDetectedDEPRECATED @5 :Bool; hasGpsDEPRECATED @6 :Bool; fanSpeedRpmDEPRECATED @11 :UInt16; @@ -666,7 +693,6 @@ struct ControlsState @0x97ff69c53601abf1 { aTarget @35 :Float32; curvature @37 :Float32; # path curvature from vehicle model desiredCurvature @61 :Float32; # lag adjusted curvatures used by lateral controllers - desiredCurvatureRate @62 :Float32; forceDecel @51 :Bool; # UI alerts @@ -688,8 +714,8 @@ struct ControlsState @0x97ff69c53601abf1 { angleState @58 :LateralAngleState; debugState @59 :LateralDebugState; torqueState @60 :LateralTorqueState; - curvatureState @65 :LateralCurvatureState; + curvatureStateDEPRECATED @65 :LateralCurvatureState; lqrStateDEPRECATED @55 :LateralLQRState; } @@ -824,6 +850,7 @@ struct ControlsState @0x97ff69c53601abf1 { steerOverrideDEPRECATED @20 :Bool; steeringAngleDesiredDegDEPRECATED @29 :Float32; canMonoTimesDEPRECATED @21 :List(UInt64); + desiredCurvatureRateDEPRECATED @62 :Float32; } # All SI units and in device frame @@ -875,7 +902,8 @@ struct ModelDataV2 { locationMonoTime @24 :UInt64; # e2e lateral planner - lateralPlannerSolution @25: LateralPlannerSolution; + lateralPlannerSolutionDEPRECATED @25: LateralPlannerSolution; + action @26: Action; struct LeadDataV2 { prob @0 :Float32; # probability that car is your lead at time t @@ -913,6 +941,9 @@ struct ModelDataV2 { desireState @5 :List(Float32); disengagePredictions @6 :DisengagePredictions; hardBrakePredicted @7 :Bool; + laneChangeState @8 :LaneChangeState; + laneChangeDirection @9 :LaneChangeDirection; + # deprecated brakeDisengageProbDEPRECATED @2 :Float32; @@ -954,6 +985,9 @@ struct ModelDataV2 { yawRateStd @7 :List(Float32); } + struct Action { + desiredCurvature @0 :Float32; + } } struct EncodeIndex { @@ -1844,11 +1878,12 @@ struct QcomGnss @0xde94674b07ae51c1 { } struct Clocks { - bootTimeNanos @0 :UInt64; - monotonicNanos @1 :UInt64; - monotonicRawNanos @2 :UInt64; - wallTimeNanos @3 :UInt64; - modemUptimeMillis @4 :UInt64; + wallTimeNanos @3 :UInt64; # unix epoch time + + bootTimeNanosDEPRECATED @0 :UInt64; + monotonicNanosDEPRECATED @1 :UInt64; + monotonicRawNanosDEPRECATD @2 :UInt64; + modemUptimeMillisDEPRECATED @4 :UInt64; } struct LiveMpcData { @@ -2167,6 +2202,8 @@ struct EncodeData { data @1 :Data; header @2 :Data; unixTimestampNanos @3 :UInt64; + width @4 :UInt32; + height @5 :UInt32; } struct UserFlag { @@ -2214,7 +2251,6 @@ struct Event { carState @22 :Car.CarState; carControl @23 :Car.CarControl; longitudinalPlan @24 :LongitudinalPlan; - lateralPlan @64 :LateralPlan; uiPlan @106 :UiPlan; ubloxGnss @34 :UbloxGnss; ubloxRaw @39 :Data; @@ -2226,7 +2262,7 @@ struct Event { liveTorqueParameters @94 :LiveTorqueParametersData; cameraOdometry @63 :CameraOdometry; thumbnail @66: Thumbnail; - carEvents @68: List(Car.CarEvent); + onroadEvents @68: List(Car.CarEvent); carParams @69: Car.CarParams; driverMonitoringState @71: DriverMonitoringState; liveLocationKalman @72 :LiveLocationKalman; @@ -2335,5 +2371,6 @@ struct Event { pandaStateDEPRECATED @12 :PandaState; driverStateDEPRECATED @59 :DriverStateDEPRECATED; sensorEventsDEPRECATED @11 :List(SensorEventData); + lateralPlanDEPRECATED @64 :LateralPlan; } } diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 57675212f4..ddc0866849 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -22,7 +22,6 @@ assert delete_fake_prefix assert wait_for_one_event NO_TRAVERSAL_LIMIT = 2**64-1 -AVG_FREQ_HISTORY = 100 context = Context() @@ -41,10 +40,13 @@ def log_from_bytes(dat: bytes) -> capnp.lib.capnp._DynamicStructReader: return msg -def new_message(service: Optional[str] = None, size: Optional[int] = None) -> capnp.lib.capnp._DynamicStructBuilder: - dat = log.Event.new_message() - dat.logMonoTime = int(time.monotonic() * 1e9) - dat.valid = True +def new_message(service: Optional[str], size: Optional[int] = None, **kwargs) -> capnp.lib.capnp._DynamicStructBuilder: + args = { + 'valid': False, + 'logMonoTime': int(time.monotonic() * 1e9), + **kwargs + } + dat = log.Event.new_message(**args) if service is not None: if size is None: dat.init(service) @@ -114,14 +116,14 @@ def recv_sock(sock: SubSocket, wait: bool = False) -> Optional[capnp.lib.capnp._ while 1: if wait and dat is None: - rcv = sock.receive() + recv = sock.receive() else: - rcv = sock.receive(non_blocking=True) + recv = sock.receive(non_blocking=True) - if rcv is None: # Timeout hit + if recv is None: # Timeout hit break - dat = rcv + dat = recv if dat is not None: dat = log_from_bytes(dat) @@ -152,53 +154,76 @@ def recv_one_retry(sock: SubSocket) -> capnp.lib.capnp._DynamicStructReader: class SubMaster: - def __init__(self, services: List[str], poll: Optional[List[str]] = None, + def __init__(self, services: List[str], poll: Optional[str] = None, ignore_alive: Optional[List[str]] = None, ignore_avg_freq: Optional[List[str]] = None, - addr: str = "127.0.0.1"): + ignore_valid: Optional[List[str]] = None, addr: str = "127.0.0.1", frequency: Optional[float] = None): self.frame = -1 + self.seen = {s: False for s in services} self.updated = {s: False for s in services} - self.rcv_time = {s: 0. for s in services} - self.rcv_frame = {s: 0 for s in services} + self.recv_time = {s: 0. for s in services} + self.recv_frame = {s: 0 for s in services} self.alive = {s: False for s in services} self.freq_ok = {s: False for s in services} - self.recv_dts: Dict[str, Deque[float]] = {s: deque(maxlen=AVG_FREQ_HISTORY) for s in services} + self.recv_dts: Dict[str, Deque[float]] = {} self.sock = {} - self.freq = {} self.data = {} self.valid = {} self.logMonoTime = {} + self.max_freq = {} + self.min_freq = {} + self.poller = Poller() - self.non_polled_services = [s for s in services if poll is not None and - len(poll) and s not in poll] + polled_services = set([poll, ] if poll is not None else services) + self.non_polled_services = set(services) - polled_services self.ignore_average_freq = [] if ignore_avg_freq is None else ignore_avg_freq self.ignore_alive = [] if ignore_alive is None else ignore_alive - self.simulation = bool(int(os.getenv("SIMULATION", "0"))) + self.ignore_valid = [] if ignore_valid is None else ignore_valid + if bool(int(os.getenv("SIMULATION", "0"))): + self.ignore_alive = services + self.ignore_average_freq = services + + # if freq and poll aren't specified, assume the max to be conservative + assert frequency is None or poll is None, "Do not specify 'frequency' - frequency of the polled service will be used." + self.update_freq = frequency or max([SERVICE_LIST[s].frequency for s in polled_services]) for s in services: - if addr is not None: - p = self.poller if s not in self.non_polled_services else None - self.sock[s] = sub_sock(s, poller=p, addr=addr, conflate=True) - self.freq[s] = SERVICE_LIST[s].frequency + p = self.poller if s not in self.non_polled_services else None + self.sock[s] = sub_sock(s, poller=p, addr=addr, conflate=True) try: data = new_message(s) - except capnp.lib.capnp.KjException: # pylint: disable=c-extension-no-member + except capnp.lib.capnp.KjException: data = new_message(s, 0) # lists - self.data[s] = getattr(data, s) + self.data[s] = getattr(data.as_reader(), s) self.logMonoTime[s] = 0 - self.valid[s] = data.valid + self.valid[s] = True # FIXME: this should default to False + + freq = max(min([SERVICE_LIST[s].frequency, self.update_freq]), 1.) + if s == poll: + max_freq = freq + min_freq = freq + else: + max_freq = min(freq, self.update_freq) + if SERVICE_LIST[s].frequency >= 2*self.update_freq: + min_freq = self.update_freq + elif self.update_freq >= 2*SERVICE_LIST[s].frequency: + min_freq = freq + else: + min_freq = min(freq, freq / 2.) + self.max_freq[s] = max_freq*1.2 + self.min_freq[s] = min_freq*0.8 + self.recv_dts[s] = deque(maxlen=int(10*freq)) def __getitem__(self, s: str) -> capnp.lib.capnp._DynamicStructReader: return self.data[s] - def _check_avg_freq(self, s): - return self.rcv_time[s] > 1e-5 and self.freq[s] > 1e-5 and (s not in self.non_polled_services) \ - and (s not in self.ignore_average_freq) + def _check_avg_freq(self, s: str) -> bool: + return SERVICE_LIST[s].frequency > 0.99 and (s not in self.ignore_average_freq) and (s not in self.ignore_alive) - def update(self, timeout: int = 1000) -> None: + def update(self, timeout: int = 100) -> None: msgs = [] for sock in self.poller.poll(timeout): msgs.append(recv_one_or_none(sock)) @@ -216,64 +241,57 @@ class SubMaster: continue s = msg.which() + self.seen[s] = True self.updated[s] = True - if self._check_avg_freq(s): - self.recv_dts[s].append(cur_time - self.rcv_time[s]) - - self.rcv_time[s] = cur_time - self.rcv_frame[s] = self.frame + if self.recv_time[s] > 1e-5: + self.recv_dts[s].append(cur_time - self.recv_time[s]) + self.recv_time[s] = cur_time + self.recv_frame[s] = self.frame self.data[s] = getattr(msg, s) self.logMonoTime[s] = msg.logMonoTime self.valid[s] = msg.valid - if self.simulation: + for s in self.data: + if SERVICE_LIST[s].frequency > 1e-5: + # alive if delay is within 10x the expected frequency + self.alive[s] = (cur_time - self.recv_time[s]) < (10. / SERVICE_LIST[s].frequency) + + # check average frequency; slow to fall, quick to recover + dts = self.recv_dts[s] + assert dts.maxlen is not None + recent_dts = list(dts)[-int(dts.maxlen / 10):] + try: + avg_freq = 1 / (sum(dts) / len(dts)) + avg_freq_recent = 1 / (sum(recent_dts) / len(recent_dts)) + except ZeroDivisionError: + avg_freq = 0 + avg_freq_recent = 0 + + avg_freq_ok = self.min_freq[s] <= avg_freq <= self.max_freq[s] + recent_freq_ok = self.min_freq[s] <= avg_freq_recent <= self.max_freq[s] + self.freq_ok[s] = avg_freq_ok or recent_freq_ok + else: self.freq_ok[s] = True self.alive[s] = True - if not self.simulation: - for s in self.data: - # arbitrary small number to avoid float comparison. If freq is 0, we can skip the check - if self.freq[s] > 1e-5: - # alive if delay is within 10x the expected frequency - self.alive[s] = (cur_time - self.rcv_time[s]) < (10. / self.freq[s]) - - # TODO: check if update frequency is high enough to not drop messages - # freq_ok if average frequency is higher than 90% of expected frequency - if self._check_avg_freq(s): - if len(self.recv_dts[s]) > 0: - avg_dt = sum(self.recv_dts[s]) / len(self.recv_dts[s]) - expected_dt = 1 / (self.freq[s] * 0.90) - self.freq_ok[s] = (avg_dt < expected_dt) - else: - self.freq_ok[s] = False - else: - self.freq_ok[s] = True - else: - self.freq_ok[s] = True - self.alive[s] = True - - def all_alive(self, service_list=None) -> bool: - if service_list is None: # check all - service_list = self.alive.keys() + def all_alive(self, service_list: Optional[List[str]] = None) -> bool: + if service_list is None: + service_list = list(self.sock.keys()) return all(self.alive[s] for s in service_list if s not in self.ignore_alive) - def all_freq_ok(self, service_list=None) -> bool: - if service_list is None: # check all - service_list = self.alive.keys() - return all(self.freq_ok[s] for s in service_list if s not in self.ignore_alive) - - def all_valid(self, service_list=None) -> bool: - if service_list is None: # check all - service_list = self.valid.keys() - return all(self.valid[s] for s in service_list) - - def all_checks(self, service_list=None) -> bool: - if service_list is None: # check all - service_list = self.alive.keys() - return self.all_alive(service_list=service_list) \ - and self.all_freq_ok(service_list=service_list) \ - and self.all_valid(service_list=service_list) + def all_freq_ok(self, service_list: Optional[List[str]] = None) -> bool: + if service_list is None: + service_list = list(self.sock.keys()) + return all(self.freq_ok[s] for s in service_list if self._check_avg_freq(s)) + + def all_valid(self, service_list: Optional[List[str]] = None) -> bool: + if service_list is None: + service_list = list(self.sock.keys()) + return all(self.valid[s] for s in service_list if s not in self.ignore_valid) + + def all_checks(self, service_list: Optional[List[str]] = None) -> bool: + return self.all_alive(service_list) and self.all_freq_ok(service_list) and self.all_valid(service_list) class PubMaster: diff --git a/cereal/services.py b/cereal/services.py index 9c08e63525..e79f2e062a 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -53,14 +53,13 @@ services: dict[str, tuple] = { "ubloxGnss": (True, 10.), "qcomGnss": (True, 2.), "gnssMeasurements": (True, 10., 10), - "clocks": (True, 1., 1), + "clocks": (True, 0.1, 1), "ubloxRaw": (True, 20.), "liveLocationKalman": (True, 20., 5), "liveParameters": (True, 20., 5), "cameraOdometry": (True, 20., 5), - "lateralPlan": (True, 20., 5), "thumbnail": (True, 0.2, 1), - "carEvents": (True, 1., 1), + "onroadEvents": (True, 1., 1), "carParams": (True, 0.02, 1), "roadCameraState": (True, 20., 20), "driverCameraState": (True, 20., 20), diff --git a/cereal/visionipc/visionipc_client.cc b/cereal/visionipc/visionipc_client.cc index 169afbb369..e3c6d0d1ca 100644 --- a/cereal/visionipc/visionipc_client.cc +++ b/cereal/visionipc/visionipc_client.cc @@ -3,24 +3,19 @@ #include #include +#include #include "cereal/visionipc/ipc.h" #include "cereal/visionipc/visionipc_client.h" #include "cereal/visionipc/visionipc_server.h" #include "cereal/logger/logger.h" static int connect_to_vipc_server(const std::string &name, bool blocking) { - char* prefix = std::getenv("OPENPILOT_PREFIX"); - std::string path = "/tmp/"; - if (prefix) { - path = path + std::string(prefix) + "_"; - } - path = path + "visionipc_" + name; - - int socket_fd = ipc_connect(path.c_str()); + const std::string ipc_path = get_ipc_path(name); + int socket_fd = ipc_connect(ipc_path.c_str()); while (socket_fd < 0 && blocking) { std::cout << "VisionIpcClient connecting" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(100)); - socket_fd = ipc_connect(path.c_str()); + socket_fd = ipc_connect(ipc_path.c_str()); } return socket_fd; } diff --git a/cereal/visionipc/visionipc_client.h b/cereal/visionipc/visionipc_client.h index d67734d32f..970bac3a71 100644 --- a/cereal/visionipc/visionipc_client.h +++ b/cereal/visionipc/visionipc_client.h @@ -2,11 +2,8 @@ #include #include -#include -#include #include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionipc.h" #include "cereal/visionipc/visionbuf.h" class VisionIpcClient { diff --git a/cereal/visionipc/visionipc_server.cc b/cereal/visionipc/visionipc_server.cc index c51e13ea1d..da9d11f91a 100644 --- a/cereal/visionipc/visionipc_server.cc +++ b/cereal/visionipc/visionipc_server.cc @@ -22,6 +22,14 @@ std::string get_endpoint_name(std::string name, VisionStreamType type){ } } +std::string get_ipc_path(const std::string& name) { + std::string path = "/tmp/"; + if (char* prefix = std::getenv("OPENPILOT_PREFIX")) { + path += std::string(prefix) + "_"; + } + return path + "visionipc_" + name; +} + VisionIpcServer::VisionIpcServer(std::string name, cl_device_id device_id, cl_context ctx) : name(name), device_id(device_id), ctx(ctx) { msg_ctx = Context::create(); @@ -83,14 +91,8 @@ void VisionIpcServer::start_listener(){ void VisionIpcServer::listener(){ std::cout << "Starting listener for: " << name << std::endl; - char* prefix = std::getenv("OPENPILOT_PREFIX"); - std::string path = "/tmp/"; - if (prefix) { - path = path + std::string(prefix) + "_"; - } - path = path + "visionipc_" + name; - - int sock = ipc_bind(path.c_str()); + const std::string ipc_path = get_ipc_path(name); + int sock = ipc_bind(ipc_path.c_str()); assert(sock >= 0); while (!should_exit){ @@ -160,7 +162,7 @@ void VisionIpcServer::listener(){ std::cout << "Stopping listener for: " << name << std::endl; close(sock); - unlink(path.c_str()); + unlink(ipc_path.c_str()); } diff --git a/cereal/visionipc/visionipc_server.h b/cereal/visionipc/visionipc_server.h index 6ad86f1469..c494b1fcf4 100644 --- a/cereal/visionipc/visionipc_server.h +++ b/cereal/visionipc/visionipc_server.h @@ -6,10 +6,10 @@ #include #include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionipc.h" #include "cereal/visionipc/visionbuf.h" std::string get_endpoint_name(std::string name, VisionStreamType type); +std::string get_ipc_path(const std::string &name); class VisionIpcServer { private: diff --git a/common/SConscript b/common/SConscript index 97322b248d..829db6eeec 100644 --- a/common/SConscript +++ b/common/SConscript @@ -2,7 +2,6 @@ Import('env', 'envCython', 'arch') common_libs = [ 'params.cc', - 'statlog.cc', 'swaglog.cc', 'util.cc', 'i2c.cc', @@ -24,18 +23,17 @@ Export('_common', '_gpucommon') if GetOption('extras'): env.Program('tests/test_common', - ['tests/test_runner.cc', 'tests/test_util.cc', 'tests/test_swaglog.cc', 'tests/test_ratekeeper.cc'], + ['tests/test_runner.cc', 'tests/test_params.cc', 'tests/test_util.cc', 'tests/test_swaglog.cc'], LIBS=[_common, 'json11', 'zmq', 'pthread']) # Cython bindings params_python = envCython.Program('params_pyx.so', 'params_pyx.pyx', LIBS=envCython['LIBS'] + [_common, 'zmq', 'json11']) SConscript([ - 'kalman/SConscript', - 'transformations/SConscript' + 'transformations/SConscript', ]) -Import('simple_kalman_python', 'transformations_python') -common_python = [params_python, simple_kalman_python, transformations_python] +Import('transformations_python') +common_python = [params_python, transformations_python] Export('common_python') diff --git a/common/api/__init__.py b/common/api/__init__.py index 0eb8aa7627..79875023a2 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -2,7 +2,7 @@ import jwt import os import requests from datetime import datetime, timedelta -from openpilot.common.basedir import PERSIST +from openpilot.system.hardware.hw import Paths from openpilot.system.version import get_version API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') @@ -10,7 +10,7 @@ API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') class Api(): def __init__(self, dongle_id): self.dongle_id = dongle_id - with open(PERSIST+'/comma/id_rsa') as f: + with open(Paths.persist_root()+'/comma/id_rsa') as f: self.private_key = f.read() def get(self, *args, **kwargs): diff --git a/common/basedir.py b/common/basedir.py index b4486f9f08..6b4811e53c 100644 --- a/common/basedir.py +++ b/common/basedir.py @@ -1,11 +1,4 @@ import os -from pathlib import Path -from openpilot.system.hardware import PC BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) - -if PC: - PERSIST = os.path.join(str(Path.home()), ".comma", "persist") -else: - PERSIST = "/persist" diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py index a228b40256..01741c6f42 100644 --- a/common/ffi_wrapper.py +++ b/common/ffi_wrapper.py @@ -1,55 +1,8 @@ -import os -import sys -import fcntl -import hashlib import platform -from cffi import FFI + def suffix(): if platform.system() == "Darwin": return ".dylib" else: return ".so" - -def ffi_wrap(name, c_code, c_header, tmpdir="/tmp/ccache", cflags="", libraries=None): - if libraries is None: - libraries = [] - - cache = name + "_" + hashlib.sha1(c_code.encode('utf-8')).hexdigest() - try: - os.mkdir(tmpdir) - except OSError: - pass - - fd = os.open(tmpdir, 0) - fcntl.flock(fd, fcntl.LOCK_EX) - try: - sys.path.append(tmpdir) - try: - mod = __import__(cache) - except Exception: - print(f"cache miss {cache}") - compile_code(cache, c_code, c_header, tmpdir, cflags, libraries) - mod = __import__(cache) - finally: - os.close(fd) - - return mod.ffi, mod.lib - - -def compile_code(name, c_code, c_header, directory, cflags="", libraries=None): - if libraries is None: - libraries = [] - - ffibuilder = FFI() - ffibuilder.set_source(name, c_code, source_extension='.cpp', libraries=libraries) - ffibuilder.cdef(c_header) - os.environ['OPT'] = "-fwrapv -O2 -DNDEBUG -std=c++1z" - os.environ['CFLAGS'] = cflags - ffibuilder.compile(verbose=True, debug=False, tmpdir=directory) - - -def wrap_compiled(name, directory): - sys.path.append(directory) - mod = __import__(name) - return mod.ffi, mod.lib diff --git a/common/file_helpers.py b/common/file_helpers.py index 227d614d72..dea298a529 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -1,60 +1,7 @@ import os -import shutil import tempfile -from atomicwrites import AtomicWriter - - -def mkdirs_exists_ok(path): - if path.startswith(('http://', 'https://')): - raise ValueError('URL path') - try: - os.makedirs(path) - except OSError: - if not os.path.isdir(path): - raise - - -def rm_not_exists_ok(path): - try: - os.remove(path) - except OSError: - if os.path.exists(path): - raise - - -def rm_tree_or_link(path): - if os.path.islink(path): - os.unlink(path) - elif os.path.isdir(path): - shutil.rmtree(path) - - -def get_tmpdir_on_same_filesystem(path): - normpath = os.path.normpath(path) - parts = normpath.split("/") - if len(parts) > 1 and parts[1] == "scratch": - return "/scratch/tmp" - elif len(parts) > 2 and parts[2] == "runner": - return f"/{parts[1]}/runner/tmp" - return "/tmp" - - -class NamedTemporaryDir(): - def __init__(self, temp_dir=None): - self._path = tempfile.mkdtemp(dir=temp_dir) - - @property - def name(self): - return self._path - - def close(self): - shutil.rmtree(self._path) - - def __enter__(self): - return self - - def __exit__(self, exc_type, exc_value, traceback): - self.close() +import contextlib +from typing import Optional class CallbackReader: @@ -76,24 +23,16 @@ class CallbackReader: return chunk -def _get_fileobject_func(writer, temp_dir): - def _get_fileobject(): - return writer.get_fileobject(dir=temp_dir) - return _get_fileobject - -def atomic_write_on_fs_tmp(path, **kwargs): - """Creates an atomic writer using a temporary file in a temporary directory - on the same filesystem as path. - """ - # TODO(mgraczyk): This use of AtomicWriter relies on implementation details to set the temp - # directory. - writer = AtomicWriter(path, **kwargs) - return writer._open(_get_fileobject_func(writer, get_tmpdir_on_same_filesystem(path))) +@contextlib.contextmanager +def atomic_write_in_dir(path: str, mode: str = 'w', buffering: int = -1, encoding: Optional[str] = None, newline: Optional[str] = None, + overwrite: bool = False): + """Write to a file atomically using a temporary file in the same directory as the destination file.""" + dir_name = os.path.dirname(path) + if not overwrite and os.path.exists(path): + raise FileExistsError(f"File '{path}' already exists. To overwrite it, set 'overwrite' to True.") -def atomic_write_in_dir(path, **kwargs): - """Creates an atomic writer using a temporary file in the same directory - as the destination file. - """ - writer = AtomicWriter(path, **kwargs) - return writer._open(_get_fileobject_func(writer, os.path.dirname(path))) + with tempfile.NamedTemporaryFile(mode=mode, buffering=buffering, encoding=encoding, newline=newline, dir=dir_name, delete=False) as tmp_file: + yield tmp_file + tmp_file_name = tmp_file.name + os.replace(tmp_file_name, path) diff --git a/common/kalman/.gitignore b/common/kalman/.gitignore deleted file mode 100644 index d86912e7d0..0000000000 --- a/common/kalman/.gitignore +++ /dev/null @@ -1 +0,0 @@ -simple_kalman_impl.c diff --git a/common/kalman/SConscript b/common/kalman/SConscript deleted file mode 100644 index 7cba4a9a61..0000000000 --- a/common/kalman/SConscript +++ /dev/null @@ -1,5 +0,0 @@ -Import('envCython') - -simple_kalman_python = envCython.Program('simple_kalman_impl.so', 'simple_kalman_impl.pyx') - -Export('simple_kalman_python') diff --git a/common/kalman/simple_kalman.py b/common/kalman/simple_kalman.py deleted file mode 100644 index 5e1b6ce1fb..0000000000 --- a/common/kalman/simple_kalman.py +++ /dev/null @@ -1,12 +0,0 @@ -from openpilot.common.kalman.simple_kalman_impl import KF1D as KF1D -assert KF1D -import numpy as np - -def get_kalman_gain(dt, A, C, Q, R, iterations=100): - P = np.zeros_like(Q) - for _ in range(iterations): - P = A.dot(P).dot(A.T) + dt * Q - S = C.dot(P).dot(C.T) + R - K = P.dot(C.T).dot(np.linalg.inv(S)) - P = (np.eye(len(P)) - K.dot(C)).dot(P) - return K \ No newline at end of file diff --git a/common/kalman/simple_kalman_impl.pxd b/common/kalman/simple_kalman_impl.pxd deleted file mode 100644 index cb39a45bca..0000000000 --- a/common/kalman/simple_kalman_impl.pxd +++ /dev/null @@ -1,18 +0,0 @@ -# cython: language_level = 3 - -cdef class KF1D: - cdef public: - double x0_0 - double x1_0 - double K0_0 - double K1_0 - double A0_0 - double A0_1 - double A1_0 - double A1_1 - double C0_0 - double C0_1 - double A_K_0 - double A_K_1 - double A_K_2 - double A_K_3 diff --git a/common/kalman/simple_kalman_impl.pyx b/common/kalman/simple_kalman_impl.pyx deleted file mode 100644 index 16aefba2e5..0000000000 --- a/common/kalman/simple_kalman_impl.pyx +++ /dev/null @@ -1,37 +0,0 @@ -# distutils: language = c++ -# cython: language_level=3 - -cdef class KF1D: - def __init__(self, x0, A, C, K): - self.x0_0 = x0[0][0] - self.x1_0 = x0[1][0] - self.A0_0 = A[0][0] - self.A0_1 = A[0][1] - self.A1_0 = A[1][0] - self.A1_1 = A[1][1] - self.C0_0 = C[0] - self.C0_1 = C[1] - self.K0_0 = K[0][0] - self.K1_0 = K[1][0] - - self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0 - self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1 - self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0 - self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 - - def update(self, meas): - cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas - cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas - self.x0_0 = x0_0 - self.x1_0 = x1_0 - - return [self.x0_0, self.x1_0] - - @property - def x(self): - return [[self.x0_0], [self.x1_0]] - - @x.setter - def x(self, x): - self.x0_0 = x[0][0] - self.x1_0 = x[1][0] diff --git a/common/kalman/simple_kalman_old.py b/common/kalman/simple_kalman_old.py deleted file mode 100644 index d11770faf6..0000000000 --- a/common/kalman/simple_kalman_old.py +++ /dev/null @@ -1,23 +0,0 @@ -import numpy as np - - -class KF1D: - # this EKF assumes constant covariance matrix, so calculations are much simpler - # the Kalman gain also needs to be precomputed using the control module - - def __init__(self, x0, A, C, K): - self.x = x0 - self.A = A - self.C = np.atleast_2d(C) - self.K = K - - self.A_K = self.A - np.dot(self.K, self.C) - - # K matrix needs to be pre-computed as follow: - # import control - # (x, l, K) = control.dare(np.transpose(self.A), np.transpose(self.C), Q, R) - # self.K = np.transpose(K) - - def update(self, meas): - self.x = np.dot(self.A_K, self.x) + np.dot(self.K, meas) - return self.x diff --git a/common/kalman/tests/__init__.py b/common/kalman/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/common/kalman/tests/test_simple_kalman.py b/common/kalman/tests/test_simple_kalman.py deleted file mode 100644 index 32cc79fc3d..0000000000 --- a/common/kalman/tests/test_simple_kalman.py +++ /dev/null @@ -1,87 +0,0 @@ -import unittest -import random -import timeit -import numpy as np - -from openpilot.common.kalman.simple_kalman import KF1D -from openpilot.common.kalman.simple_kalman_old import KF1D as KF1D_old - - -class TestSimpleKalman(unittest.TestCase): - def setUp(self): - dt = 0.01 - x0_0 = 0.0 - x1_0 = 0.0 - A0_0 = 1.0 - A0_1 = dt - A1_0 = 0.0 - A1_1 = 1.0 - C0_0 = 1.0 - C0_1 = 0.0 - K0_0 = 0.12287673 - K1_0 = 0.29666309 - - self.kf_old = KF1D_old(x0=np.array([[x0_0], [x1_0]]), - A=np.array([[A0_0, A0_1], [A1_0, A1_1]]), - C=np.array([C0_0, C0_1]), - K=np.array([[K0_0], [K1_0]])) - - self.kf = KF1D(x0=[[x0_0], [x1_0]], - A=[[A0_0, A0_1], [A1_0, A1_1]], - C=[C0_0, C0_1], - K=[[K0_0], [K1_0]]) - - def test_getter_setter(self): - self.kf.x = [[1.0], [1.0]] - self.assertEqual(self.kf.x, [[1.0], [1.0]]) - - def update_returns_state(self): - x = self.kf.update(100) - self.assertEqual(x, self.kf.x) - - def test_old_equal_new(self): - for _ in range(1000): - v_wheel = random.uniform(0, 200) - - x_old = self.kf_old.update(v_wheel) - x = self.kf.update(v_wheel) - - # Compare the output x, verify that the error is less than 1e-4 - np.testing.assert_almost_equal(x_old[0], x[0]) - np.testing.assert_almost_equal(x_old[1], x[1]) - - def test_new_is_faster(self): - setup = """ -import numpy as np - -from openpilot.common.kalman.simple_kalman import KF1D -from openpilot.common.kalman.simple_kalman_old import KF1D as KF1D_old - -dt = 0.01 -x0_0 = 0.0 -x1_0 = 0.0 -A0_0 = 1.0 -A0_1 = dt -A1_0 = 0.0 -A1_1 = 1.0 -C0_0 = 1.0 -C0_1 = 0.0 -K0_0 = 0.12287673 -K1_0 = 0.29666309 - -kf_old = KF1D_old(x0=np.array([[x0_0], [x1_0]]), - A=np.array([[A0_0, A0_1], [A1_0, A1_1]]), - C=np.array([C0_0, C0_1]), - K=np.array([[K0_0], [K1_0]])) - -kf = KF1D(x0=[[x0_0], [x1_0]], - A=[[A0_0, A0_1], [A1_0, A1_1]], - C=[C0_0, C0_1], - K=[[K0_0], [K1_0]]) - """ - kf_speed = timeit.timeit("kf.update(1234)", setup=setup, number=10000) - kf_old_speed = timeit.timeit("kf_old.update(1234)", setup=setup, number=10000) - self.assertTrue(kf_speed < kf_old_speed / 4) - -if __name__ == "__main__": - unittest.main() diff --git a/common/logging_extra.py b/common/logging_extra.py index 5e0584c7bc..f53d503108 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -65,7 +65,7 @@ class SwagFormatter(logging.Formatter): return record_dict - def format(self, record): # noqa: A003 + def format(self, record): if self.swaglogger is None: raise Exception("must set swaglogger before calling format()") return json_robust_dumps(self.format_dict(record)) @@ -95,7 +95,7 @@ class SwagLogFileFormatter(SwagFormatter): k += "$a" return k, v - def format(self, record): # noqa: A003 + def format(self, record): if isinstance(record, str): v = json.loads(record) else: diff --git a/common/modeldata.h b/common/modeldata.h deleted file mode 100644 index 6dc02cc792..0000000000 --- a/common/modeldata.h +++ /dev/null @@ -1,38 +0,0 @@ -#pragma once - -#include -#include "common/mat.h" -#include "system/hardware/hw.h" - -const int TRAJECTORY_SIZE = 33; -const int LAT_MPC_N = 16; -const int LON_MPC_N = 32; -const float MIN_DRAW_DISTANCE = 10.0; -const float MAX_DRAW_DISTANCE = 100.0; - -const float RYG_GREEN = 0.01165; -const float RYG_YELLOW = 0.06157; - -template -constexpr std::array build_idxs(float max_val) { - std::array result{}; - for (int i = 0; i < size; ++i) { - result[i] = max_val * ((i / (double)(size - 1)) * (i / (double)(size - 1))); - } - return result; -} - -constexpr auto T_IDXS = build_idxs(10.0); -constexpr auto T_IDXS_FLOAT = build_idxs(10.0); -constexpr auto X_IDXS = build_idxs(192.0); -constexpr auto X_IDXS_FLOAT = build_idxs(192.0); - -const mat3 FCAM_INTRINSIC_MATRIX = (mat3){{2648.0, 0.0, 1928.0 / 2, - 0.0, 2648.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; - -// tici ecam focal probably wrong? magnification is not consistent across frame -// Need to retrain model before this can be changed -const mat3 ECAM_INTRINSIC_MATRIX = (mat3){{567.0, 0.0, 1928.0 / 2, - 0.0, 567.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; diff --git a/common/params.cc b/common/params.cc index 54168165a1..aef2cbdecd 100644 --- a/common/params.cc +++ b/common/params.cc @@ -4,9 +4,11 @@ #include #include +#include #include #include +#include "common/queue.h" #include "common/swaglog.h" #include "common/util.h" #include "system/hardware/hw.h" @@ -92,6 +94,8 @@ std::unordered_map keys = { {"AssistNowToken", PERSISTENT}, {"AthenadPid", PERSISTENT}, {"AthenadUploadQueue", PERSISTENT}, + {"AthenadRecentlyViewedRoutes", PERSISTENT}, + {"BootCount", PERSISTENT}, {"CalibrationParams", PERSISTENT}, {"CameraDebugExpGain", CLEAR_ON_MANAGER_START}, {"CameraDebugExpTime", CLEAR_ON_MANAGER_START}, @@ -114,13 +118,14 @@ std::unordered_map keys = { {"DoReboot", CLEAR_ON_MANAGER_START}, {"DoShutdown", CLEAR_ON_MANAGER_START}, {"DoUninstall", CLEAR_ON_MANAGER_START}, - {"ExperimentalLongitudinalEnabled", PERSISTENT}, + {"ExperimentalLongitudinalEnabled", PERSISTENT | DEVELOPMENT_ONLY}, {"ExperimentalMode", PERSISTENT}, {"ExperimentalModeConfirmed", PERSISTENT}, {"FirmwareQueryDone", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"ForcePowerDown", PERSISTENT}, {"GitBranch", PERSISTENT}, {"GitCommit", PERSISTENT}, + {"GitCommitDate", PERSISTENT}, {"GitDiff", PERSISTENT}, {"GithubSshKeys", PERSISTENT}, {"GithubUsername", PERSISTENT}, @@ -142,16 +147,13 @@ std::unordered_map keys = { {"IsReleaseBranch", CLEAR_ON_MANAGER_START}, {"IsTakingSnapshot", CLEAR_ON_MANAGER_START}, {"IsTestedBranch", CLEAR_ON_MANAGER_START}, - {"IsUpdateAvailable", CLEAR_ON_MANAGER_START}, {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"LaikadEphemerisV3", PERSISTENT | DONT_LOG}, {"LanguageSetting", PERSISTENT}, {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, {"LastOffroadStatusPacket", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"LastPowerDropDetected", CLEAR_ON_MANAGER_START}, - {"LastSystemShutdown", CLEAR_ON_MANAGER_START}, {"LastUpdateException", CLEAR_ON_MANAGER_START}, {"LastUpdateTime", PERSISTENT}, {"LiveParameters", PERSISTENT}, @@ -162,7 +164,7 @@ std::unordered_map keys = { {"NavPastDestinations", PERSISTENT}, {"NavSettingLeftSide", PERSISTENT}, {"NavSettingTime24h", PERSISTENT}, - {"NavdRender", PERSISTENT}, + {"NetworkMetered", PERSISTENT}, {"ObdMultiplexingChanged", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"ObdMultiplexingEnabled", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"Offroad_BadNvme", CLEAR_ON_MANAGER_START}, @@ -182,22 +184,19 @@ std::unordered_map keys = { {"PandaHeartbeatLost", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"PandaSomResetTriggered", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"PandaSignatures", CLEAR_ON_MANAGER_START}, - {"Passive", PERSISTENT}, {"PrimeType", PERSISTENT}, {"RecordFront", PERSISTENT}, {"RecordFrontLock", PERSISTENT}, // for the internal fleet {"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"ShouldDoUpdate", CLEAR_ON_MANAGER_START}, {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"SshEnabled", PERSISTENT}, - {"SubscriberInfo", PERSISTENT}, {"TermsVersion", PERSISTENT}, {"Timezone", PERSISTENT}, {"TrainingVersion", PERSISTENT}, {"UbloxAvailable", PERSISTENT}, {"UpdateAvailable", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"UpdateFailedCount", CLEAR_ON_MANAGER_START}, - {"UpdaterAvailableBranches", CLEAR_ON_MANAGER_START}, + {"UpdaterAvailableBranches", PERSISTENT}, {"UpdaterCurrentDescription", CLEAR_ON_MANAGER_START}, {"UpdaterCurrentReleaseNotes", CLEAR_ON_MANAGER_START}, {"UpdaterFetchAvailable", CLEAR_ON_MANAGER_START}, @@ -205,17 +204,24 @@ std::unordered_map keys = { {"UpdaterNewReleaseNotes", CLEAR_ON_MANAGER_START}, {"UpdaterState", CLEAR_ON_MANAGER_START}, {"UpdaterTargetBranch", CLEAR_ON_MANAGER_START}, + {"UpdaterLastFetchTime", PERSISTENT}, {"Version", PERSISTENT}, {"VisionRadarToggle", PERSISTENT}, - {"WheeledBody", PERSISTENT}, }; } // namespace Params::Params(const std::string &path) { - prefix = "/" + util::getenv("OPENPILOT_PREFIX", "d"); - params_path = ensure_params_path(prefix, path); + params_prefix = "/" + util::getenv("OPENPILOT_PREFIX", "d"); + params_path = ensure_params_path(params_prefix, path); +} + +Params::~Params() { + if (future.valid()) { + future.wait(); + } + assert(queue.empty()); } std::vector Params::allKeys() const { @@ -328,3 +334,20 @@ void Params::clearAll(ParamKeyType key_type) { fsync_dir(getParamPath()); } + +void Params::putNonBlocking(const std::string &key, const std::string &val) { + queue.push(std::make_pair(key, val)); + // start thread on demand + if (!future.valid() || future.wait_for(std::chrono::milliseconds(0)) == std::future_status::ready) { + future = std::async(std::launch::async, &Params::asyncWriteThread, this); + } +} + +void Params::asyncWriteThread() { + // TODO: write the latest one if a key has multiple values in the queue. + std::pair p; + while (queue.try_pop(p, 0)) { + // Params::put is Thread-Safe + put(p.first, p.second); + } +} diff --git a/common/params.h b/common/params.h index fbe0bba6b0..d726a6185f 100644 --- a/common/params.h +++ b/common/params.h @@ -1,21 +1,28 @@ #pragma once +#include #include #include +#include +#include #include +#include "common/queue.h" + enum ParamKeyType { PERSISTENT = 0x02, CLEAR_ON_MANAGER_START = 0x04, CLEAR_ON_ONROAD_TRANSITION = 0x08, CLEAR_ON_OFFROAD_TRANSITION = 0x10, DONT_LOG = 0x20, + DEVELOPMENT_ONLY = 0x40, ALL = 0xFFFFFFFF }; class Params { public: explicit Params(const std::string &path = {}); + ~Params(); // Not copyable. Params(const Params&) = delete; Params& operator=(const Params&) = delete; @@ -24,7 +31,7 @@ public: bool checkKey(const std::string &key); ParamKeyType getKeyType(const std::string &key); inline std::string getParamPath(const std::string &key = {}) { - return params_path + prefix + (key.empty() ? "" : "/" + key); + return params_path + params_prefix + (key.empty() ? "" : "/" + key); } // Delete a value @@ -46,8 +53,18 @@ public: inline int putBool(const std::string &key, bool val) { return put(key.c_str(), val ? "1" : "0", 1); } + void putNonBlocking(const std::string &key, const std::string &val); + inline void putBoolNonBlocking(const std::string &key, bool val) { + putNonBlocking(key, val ? "1" : "0"); + } private: + void asyncWriteThread(); + std::string params_path; - std::string prefix; + std::string params_prefix; + + // for nonblocking write + std::future future; + SafeQueue> queue; }; diff --git a/common/params.py b/common/params.py index ea8ac7514a..66808083dc 100644 --- a/common/params.py +++ b/common/params.py @@ -1,10 +1,7 @@ -from openpilot.common.params_pyx import Params, ParamKeyType, UnknownKeyName, put_nonblocking, \ - put_bool_nonblocking +from openpilot.common.params_pyx import Params, ParamKeyType, UnknownKeyName assert Params assert ParamKeyType assert UnknownKeyName -assert put_nonblocking -assert put_bool_nonblocking if __name__ == "__main__": import sys diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index de52c490b3..535514e521 100644 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -3,7 +3,6 @@ from libcpp cimport bool from libcpp.string cimport string from libcpp.vector cimport vector -import threading cdef extern from "common/params.h": cpdef enum ParamKeyType: @@ -11,6 +10,7 @@ cdef extern from "common/params.h": CLEAR_ON_MANAGER_START CLEAR_ON_ONROAD_TRANSITION CLEAR_ON_OFFROAD_TRANSITION + DEVELOPMENT_ONLY ALL cdef cppclass c_Params "Params": @@ -19,6 +19,8 @@ cdef extern from "common/params.h": bool getBool(string, bool) nogil int remove(string) nogil int put(string, string) nogil + void putNonBlocking(string, string) nogil + void putBoolNonBlocking(string, bool) nogil int putBool(string, bool) nogil bool checkKey(string) nogil string getParamPath(string) nogil @@ -27,7 +29,7 @@ cdef extern from "common/params.h": def ensure_bytes(v): - return v.encode() if isinstance(v, str) else v; + return v.encode() if isinstance(v, str) else v class UnknownKeyName(Exception): pass @@ -79,7 +81,7 @@ cdef class Params: """ Warning: This function blocks until the param is written to disk! In very rare cases this can take over a second, and your code will hang. - Use the put_nonblocking helper function in time sensitive code, but + Use the put_nonblocking, put_bool_nonblocking in time sensitive code, but in general try to avoid writing params as much as possible. """ cdef string k = self.check_key(key) @@ -92,6 +94,17 @@ cdef class Params: with nogil: self.p.putBool(k, val) + def put_nonblocking(self, key, dat): + cdef string k = self.check_key(key) + cdef string dat_bytes = ensure_bytes(dat) + with nogil: + self.p.putNonBlocking(k, dat_bytes) + + def put_bool_nonblocking(self, key, bool val): + cdef string k = self.check_key(key) + with nogil: + self.p.putBoolNonBlocking(k, val) + def remove(self, key): cdef string k = self.check_key(key) with nogil: @@ -103,9 +116,3 @@ cdef class Params: def all_keys(self): return self.p.allKeys() - -def put_nonblocking(key, val, d=""): - threading.Thread(target=lambda: Params(d).put(key, val)).start() - -def put_bool_nonblocking(key, bool val, d=""): - threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() diff --git a/common/prefix.py b/common/prefix.py new file mode 100644 index 0000000000..d027e3e5a1 --- /dev/null +++ b/common/prefix.py @@ -0,0 +1,52 @@ +import os +import shutil +import uuid + +from typing import Optional + +from openpilot.common.params import Params +from openpilot.system.hardware.hw import Paths +from openpilot.system.hardware.hw import DEFAULT_DOWNLOAD_CACHE_ROOT + +class OpenpilotPrefix: + def __init__(self, prefix: Optional[str] = None, clean_dirs_on_exit: bool = True, shared_download_cache: bool = False): + self.prefix = prefix if prefix else str(uuid.uuid4().hex[0:15]) + self.msgq_path = os.path.join('/dev/shm', self.prefix) + self.clean_dirs_on_exit = clean_dirs_on_exit + self.shared_download_cache = shared_download_cache + + def __enter__(self): + self.original_prefix = os.environ.get('OPENPILOT_PREFIX', None) + os.environ['OPENPILOT_PREFIX'] = self.prefix + try: + os.mkdir(self.msgq_path) + except FileExistsError: + pass + os.makedirs(Paths.log_root(), exist_ok=True) + + if self.shared_download_cache: + os.environ["COMMA_CACHE"] = DEFAULT_DOWNLOAD_CACHE_ROOT + + return self + + def __exit__(self, exc_type, exc_obj, exc_tb): + if self.clean_dirs_on_exit: + self.clean_dirs() + try: + del os.environ['OPENPILOT_PREFIX'] + if self.original_prefix is not None: + os.environ['OPENPILOT_PREFIX'] = self.original_prefix + except KeyError: + pass + return False + + def clean_dirs(self): + symlink_path = Params().get_param_path() + if os.path.exists(symlink_path): + shutil.rmtree(os.path.realpath(symlink_path), ignore_errors=True) + os.remove(symlink_path) + shutil.rmtree(self.msgq_path, ignore_errors=True) + shutil.rmtree(Paths.log_root(), ignore_errors=True) + if not os.environ.get("COMMA_CACHE", False): + shutil.rmtree(Paths.download_cache_root(), ignore_errors=True) + shutil.rmtree(Paths.comma_home(), ignore_errors=True) diff --git a/common/profiler.py b/common/profiler.py deleted file mode 100644 index 8b1a7a8cfa..0000000000 --- a/common/profiler.py +++ /dev/null @@ -1,45 +0,0 @@ -import time - -class Profiler(): - def __init__(self, enabled=False): - self.enabled = enabled - self.cp = {} - self.cp_ignored = [] - self.iter = 0 - self.start_time = time.time() - self.last_time = self.start_time - self.tot = 0. - - def reset(self, enabled=False): - self.enabled = enabled - self.cp = {} - self.cp_ignored = [] - self.iter = 0 - self.start_time = time.time() - self.last_time = self.start_time - - def checkpoint(self, name, ignore=False): - # ignore flag needed when benchmarking threads with ratekeeper - if not self.enabled: - return - tt = time.time() - if name not in self.cp: - self.cp[name] = 0. - if ignore: - self.cp_ignored.append(name) - self.cp[name] += tt - self.last_time - if not ignore: - self.tot += tt - self.last_time - self.last_time = tt - - def display(self): - if not self.enabled: - return - self.iter += 1 - print("******* Profiling %d *******" % self.iter) - for n, ms in sorted(self.cp.items(), key=lambda x: -x[1]): - if n in self.cp_ignored: - print("%30s: %9.2f avg: %7.2f percent: %3.0f IGNORED" % (n, ms*1000.0, ms*1000.0/self.iter, ms/self.tot*100)) - else: - print("%30s: %9.2f avg: %7.2f percent: %3.0f" % (n, ms*1000.0, ms*1000.0/self.iter, ms/self.tot*100)) - print(f"Iter clock: {self.tot / self.iter:2.6f} TOTAL: {self.tot:2.2f}") diff --git a/common/realtime.py b/common/realtime.py index 05e19e770f..a398146166 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -78,7 +78,7 @@ class Ratekeeper: time.sleep(self._remaining) return lagged - # this only monitor the cumulative lag, but does not enforce a rate + # Monitors the cumulative lag, but does not enforce a rate def monitor_time(self) -> bool: prev = self._last_monitor_time self._last_monitor_time = time.monotonic() diff --git a/common/retry.py b/common/retry.py new file mode 100644 index 0000000000..9bd4ac9522 --- /dev/null +++ b/common/retry.py @@ -0,0 +1,30 @@ +import time +import functools + +from openpilot.common.swaglog import cloudlog + + +def retry(attempts=3, delay=1.0, ignore_failure=False): + def decorator(func): + @functools.wraps(func) + def wrapper(*args, **kwargs): + for _ in range(attempts): + try: + return func(*args, **kwargs) + except Exception: + cloudlog.exception(f"{func.__name__} failed, trying again") + time.sleep(delay) + + if ignore_failure: + cloudlog.error(f"{func.__name__} failed after retry") + else: + raise Exception(f"{func.__name__} failed after retry") + return wrapper + return decorator + + +if __name__ == "__main__": + @retry(attempts=10) + def abc(): + raise ValueError("abc failed :(") + abc() diff --git a/common/simple_kalman.py b/common/simple_kalman.py new file mode 100644 index 0000000000..194b27204b --- /dev/null +++ b/common/simple_kalman.py @@ -0,0 +1,54 @@ +import numpy as np + + +def get_kalman_gain(dt, A, C, Q, R, iterations=100): + P = np.zeros_like(Q) + for _ in range(iterations): + P = A.dot(P).dot(A.T) + dt * Q + S = C.dot(P).dot(C.T) + R + K = P.dot(C.T).dot(np.linalg.inv(S)) + P = (np.eye(len(P)) - K.dot(C)).dot(P) + return K + + +class KF1D: + # this EKF assumes constant covariance matrix, so calculations are much simpler + # the Kalman gain also needs to be precomputed using the control module + + def __init__(self, x0, A, C, K): + self.x0_0 = x0[0][0] + self.x1_0 = x0[1][0] + self.A0_0 = A[0][0] + self.A0_1 = A[0][1] + self.A1_0 = A[1][0] + self.A1_1 = A[1][1] + self.C0_0 = C[0] + self.C0_1 = C[1] + self.K0_0 = K[0][0] + self.K1_0 = K[1][0] + + self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0 + self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1 + self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0 + self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + + # K matrix needs to be pre-computed as follow: + # import control + # (x, l, K) = control.dare(np.transpose(self.A), np.transpose(self.C), Q, R) + # self.K = np.transpose(K) + + def update(self, meas): + #self.x = np.dot(self.A_K, self.x) + np.dot(self.K, meas) + x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + self.x0_0 = x0_0 + self.x1_0 = x1_0 + return [self.x0_0, self.x1_0] + + @property + def x(self): + return [[self.x0_0], [self.x1_0]] + + def set_x(self, x): + self.x0_0 = x[0][0] + self.x1_0 = x[1][0] diff --git a/common/statlog.cc b/common/statlog.cc deleted file mode 100644 index 587f3e8620..0000000000 --- a/common/statlog.cc +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef _GNU_SOURCE -#define _GNU_SOURCE -#endif - -#include "common/statlog.h" -#include "common/util.h" - -#include -#include -#include -#include - -class StatlogState : public LogState { - public: - StatlogState() : LogState("ipc:///tmp/stats") {} -}; - -static StatlogState s = {}; - -static void log(const char* metric_type, const char* metric, const char* fmt, ...) { - std::lock_guard lk(s.lock); - if (!s.initialized) s.initialize(); - - char* value_buf = nullptr; - va_list args; - va_start(args, fmt); - int ret = vasprintf(&value_buf, fmt, args); - va_end(args); - - if (ret > 0 && value_buf) { - char* line_buf = nullptr; - ret = asprintf(&line_buf, "%s:%s|%s", metric, value_buf, metric_type); - if (ret > 0 && line_buf) { - zmq_send(s.sock, line_buf, ret, ZMQ_NOBLOCK); - free(line_buf); - } - free(value_buf); - } -} - -void statlog_log(const char* metric_type, const char* metric, int value) { - log(metric_type, metric, "%d", value); -} - -void statlog_log(const char* metric_type, const char* metric, float value) { - log(metric_type, metric, "%f", value); -} diff --git a/common/statlog.h b/common/statlog.h deleted file mode 100644 index 5d223bb666..0000000000 --- a/common/statlog.h +++ /dev/null @@ -1,10 +0,0 @@ -#pragma once - -#define STATLOG_GAUGE "g" -#define STATLOG_SAMPLE "sa" - -void statlog_log(const char* metric_type, const char* metric, int value); -void statlog_log(const char* metric_type, const char* metric, float value); - -#define statlog_gauge(metric, value) statlog_log(STATLOG_GAUGE, metric, value) -#define statlog_sample(metric, value) statlog_log(STATLOG_SAMPLE, metric, value) diff --git a/common/swaglog.cc b/common/swaglog.cc index bcd597a257..7864a6355a 100644 --- a/common/swaglog.cc +++ b/common/swaglog.cc @@ -5,30 +5,29 @@ #include "common/swaglog.h" #include -#include -#include #include #include #include #include +#include #include "third_party/json11/json11.hpp" - -#include "common/util.h" #include "common/version.h" #include "system/hardware/hw.h" -class SwaglogState : public LogState { - public: - SwaglogState() : LogState(Path::swaglog_ipc().c_str()) {} +class SwaglogState { +public: + SwaglogState() { + zctx = zmq_ctx_new(); + sock = zmq_socket(zctx, ZMQ_PUSH); - json11::Json::object ctx_j; + // Timeout on shutdown for messages to be received by the logging process + int timeout = 100; + zmq_setsockopt(sock, ZMQ_LINGER, &timeout, sizeof(timeout)); + zmq_connect(sock, Path::swaglog_ipc().c_str()); - inline void initialize() { - ctx_j = json11::Json::object {}; print_level = CLOUDLOG_WARNING; - const char* print_lvl = getenv("LOGPRINT"); - if (print_lvl) { + if (const char* print_lvl = getenv("LOGPRINT")) { if (strcmp(print_lvl, "debug") == 0) { print_level = CLOUDLOG_DEBUG; } else if (strcmp(print_lvl, "info") == 0) { @@ -38,39 +37,53 @@ class SwaglogState : public LogState { } } - // openpilot bindings - char* dongle_id = getenv("DONGLE_ID"); - if (dongle_id) { + ctx_j = json11::Json::object{}; + if (char* dongle_id = getenv("DONGLE_ID")) { ctx_j["dongle_id"] = dongle_id; } - char* daemon_name = getenv("MANAGER_DAEMON"); - if (daemon_name) { + if (char* git_origin = getenv("GIT_ORIGIN")) { + ctx_j["origin"] = git_origin; + } + if (char* git_branch = getenv("GIT_BRANCH")) { + ctx_j["branch"] = git_branch; + } + if (char* git_commit = getenv("GIT_COMMIT")) { + ctx_j["commit"] = git_commit; + } + if (char* daemon_name = getenv("MANAGER_DAEMON")) { ctx_j["daemon"] = daemon_name; } ctx_j["version"] = COMMA_VERSION; ctx_j["dirty"] = !getenv("CLEAN"); - - // device type ctx_j["device"] = Hardware::get_name(); - LogState::initialize(); } + + ~SwaglogState() { + zmq_close(sock); + zmq_ctx_destroy(zctx); + } + + void log(int levelnum, const char* filename, int lineno, const char* func, const char* msg, const std::string& log_s) { + std::lock_guard lk(lock); + if (levelnum >= print_level) { + printf("%s: %s\n", filename, msg); + } + zmq_send(sock, log_s.data(), log_s.length(), ZMQ_NOBLOCK); + } + + std::mutex lock; + void* zctx = nullptr; + void* sock = nullptr; + int print_level; + json11::Json::object ctx_j; }; -static SwaglogState s = {}; bool LOG_TIMESTAMPS = getenv("LOG_TIMESTAMPS"); uint32_t NO_FRAME_ID = std::numeric_limits::max(); -static void log(int levelnum, const char* filename, int lineno, const char* func, const char* msg, const std::string& log_s) { - if (levelnum >= s.print_level) { - printf("%s: %s\n", filename, msg); - } - zmq_send(s.sock, log_s.data(), log_s.length(), ZMQ_NOBLOCK); -} - static void cloudlog_common(int levelnum, const char* filename, int lineno, const char* func, char* msg_buf, const json11::Json::object &msg_j={}) { - std::lock_guard lk(s.lock); - if (!s.initialized) s.initialize(); + static SwaglogState s; json11::Json::object log_j = json11::Json::object { {"ctx", s.ctx_j}, @@ -89,7 +102,7 @@ static void cloudlog_common(int levelnum, const char* filename, int lineno, cons std::string log_s; log_s += (char)levelnum; ((json11::Json)log_j).dump(log_s); - log(levelnum, filename, lineno, func, msg_buf, log_s); + s.log(levelnum, filename, lineno, func, msg_buf, log_s); free(msg_buf); } diff --git a/system/swaglog.py b/common/swaglog.py similarity index 100% rename from system/swaglog.py rename to common/swaglog.py diff --git a/common/time.py b/common/time.py index b9da106fd0..f2e49eb546 100644 --- a/common/time.py +++ b/common/time.py @@ -1,6 +1,6 @@ import datetime -MIN_DATE = datetime.datetime(year=2023, month=6, day=1) +MIN_DATE = datetime.datetime(year=2024, month=1, day=28) def system_time_valid(): - return datetime.datetime.now() > MIN_DATE \ No newline at end of file + return datetime.datetime.now() > MIN_DATE diff --git a/common/transformations/transformations.pxd b/common/transformations/transformations.pxd index 7af0098701..964adf06ec 100644 --- a/common/transformations/transformations.pxd +++ b/common/transformations/transformations.pxd @@ -1,4 +1,4 @@ -#cython: language_level=3 +# cython: language_level=3 from libcpp cimport bool cdef extern from "orientation.cc": diff --git a/common/transformations/transformations.pyx b/common/transformations/transformations.pyx index c5cb9e0056..ae045c369d 100644 --- a/common/transformations/transformations.pyx +++ b/common/transformations/transformations.pyx @@ -17,7 +17,6 @@ from openpilot.common.transformations.transformations cimport ecef2geodetic as e from openpilot.common.transformations.transformations cimport LocalCoord_c -import cython import numpy as np cimport numpy as np @@ -34,14 +33,14 @@ cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): return Matrix3(m.data) cdef ECEF list2ecef(ecef): - cdef ECEF e; + cdef ECEF e e.x = ecef[0] e.y = ecef[1] e.z = ecef[2] return e cdef NED list2ned(ned): - cdef NED n; + cdef NED n n.n = ned[0] n.e = ned[1] n.d = ned[2] @@ -61,7 +60,7 @@ def euler2quat_single(euler): def quat2euler_single(quat): cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) - cdef Vector3 e = quat2euler_c(q); + cdef Vector3 e = quat2euler_c(q) return [e(0), e(1), e(2)] def quat2rot_single(quat): diff --git a/common/util.h b/common/util.h index 5c0ef7fec5..0cbad5bd31 100644 --- a/common/util.h +++ b/common/util.h @@ -3,7 +3,6 @@ #include #include #include -#include #include #include @@ -180,36 +179,3 @@ void update_max_atomic(std::atomic& max, T const& value) { T prev = max; while (prev < value && !max.compare_exchange_weak(prev, value)) {} } - -class LogState { - public: - bool initialized = false; - std::mutex lock; - void *zctx = nullptr; - void *sock = nullptr; - int print_level; - std::string endpoint; - - LogState(std::string _endpoint) { - endpoint = _endpoint; - } - - inline void initialize() { - zctx = zmq_ctx_new(); - sock = zmq_socket(zctx, ZMQ_PUSH); - - // Timeout on shutdown for messages to be received by the logging process - int timeout = 100; - zmq_setsockopt(sock, ZMQ_LINGER, &timeout, sizeof(timeout)); - - zmq_connect(sock, endpoint.c_str()); - initialized = true; - } - - ~LogState() { - if (initialized) { - zmq_close(sock); - zmq_ctx_destroy(zctx); - } - } -}; diff --git a/common/version.h b/common/version.h index 946f6a1fec..787bc897d7 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.9.5" +#define COMMA_VERSION "0.9.6" diff --git a/docs/CARS.md b/docs/CARS.md index 044db1f0ec..6d3ee71659 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,37 +4,40 @@ A supported vehicle is one that just works when you install a comma device. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 268 Supported Cars +# 279 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Acura|RDX 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Buick|LaCrosse 2017-19[4](#footnotes)|Driver Confidence Package 2|openpilot|18 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-II connector
- 1 comma 3X
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Cadillac|Escalade 2017[4](#footnotes)|Driver Assist Package|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-II connector
- 1 comma 3X
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Cadillac|Escalade ESV 2016[4](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-II connector
- 1 comma 3X
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Cadillac|Escalade ESV 2019[4](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-II connector
- 1 comma 3X
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Chevrolet|Equinox 2019-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[1](#footnotes)|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chevrolet|Trailblazer 2021-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 GM connector
- 1 comma 3X
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chevrolet|Volt 2017-18[4](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 OBD-II connector
- 1 comma 3X
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Chrysler|Pacifica 2021-23|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Chrysler|Pacifica Hybrid 2017|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Chrysler|Pacifica Hybrid 2018|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Chrysler|Pacifica Hybrid 2019-23|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |comma|body|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None|| +|Dodge|Durango 2020-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Ford|Bronco Sport 2021-22|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Ford|Escape 2020-22|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ford|Explorer 2020-22|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Ford|Explorer 2020-23|Co-Pilot360 Assist+|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Ford|Focus 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Ford|Kuga 2020-22|Adaptive Cruise Control with Lane Centering|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Ford|Maverick 2022|LARIAT Luxury|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -60,7 +63,7 @@ A supported vehicle is one that just works when you install a comma device. All |Honda|Civic Hatchback 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch B connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|CR-V 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|CR-V Hybrid 2017-19|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Honda|CR-V Hybrid 2017-20|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|e 2020|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -71,8 +74,9 @@ A supported vehicle is one that just works when you install a comma device. All |Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|Passport 2019-23|All|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Honda|Ridgeline 2017-23|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Honda|Ridgeline 2017-24|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Azera 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Azera Hybrid 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Azera Hybrid 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Custin 2023|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Elantra 2017-18|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai B connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -96,25 +100,26 @@ A supported vehicle is one that just works when you install a comma device. All |Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai G connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Kona Electric 2022-23|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai O connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Kona Electric (with HDA II, Korea only) 2023[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai R connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai I connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai I connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Palisade 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Cruz 2022-23[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Santa Fe 2019-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Santa Cruz 2022-23[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Santa Fe 2019-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Santa Fe 2021-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Santa Fe Hybrid 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Santa Fe Plug-in Hybrid 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Sonata 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Sonata Hybrid 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Staria 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson 2022[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Tucson 2023[6](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Tucson 2022[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Tucson 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Tucson Hybrid 2022-24[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Carnival 2023-24[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Carnival 2022-24[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Carnival (China only) 2023[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|EV6 (Southeast Asia only) 2022-23[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -130,10 +135,13 @@ A supported vehicle is one that just works when you install a comma device. All |Kia|Niro EV 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Niro EV 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Niro EV 2023[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Niro Hybrid 2021-22|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Niro Hybrid 2023[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Niro Plug-in Hybrid 2018-19|All|Stock|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Niro Plug-in Hybrid 2020|All|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Niro Plug-in Hybrid 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai D connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Niro Plug-in Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai F connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Optima 2017|Advanced Smart Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai B connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Optima 2019-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai G connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Optima Hybrid 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai H connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -143,7 +151,7 @@ A supported vehicle is one that just works when you install a comma device. All |Kia|Sorento 2021-23[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Sorento Hybrid 2021-23[6](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Sorento Plug-in Hybrid 2022-23[6](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Kia|Sportage 2023[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Sportage 2023[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Sportage Hybrid 2023[6](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Stinger 2018-20|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai C connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Stinger 2022-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -151,11 +159,12 @@ A supported vehicle is one that just works when you install a comma device. All |Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|ES 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|ES 2019-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|ES Hybrid 2017-18|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|ES Hybrid 2019-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lexus|ES Hybrid 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lexus|ES Hybrid 2019-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|GS F 2016|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|IS 2022-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lexus|LC 2024|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|NX 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|NX Hybrid 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -169,35 +178,35 @@ A supported vehicle is one that just works when you install a comma device. All |Lexus|RX Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|UX Hybrid 2019-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lincoln|Aviator 2020-21|Co-Pilot360 Plus|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|MAN|eTGE 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|MAN|TGE 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|MAN|eTGE 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|MAN|TGE 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Mazda|CX-5 2022-24|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Mazda|CX-9 2021-23|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Mazda connector
- 1 RJ45 cable (7 ft)
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan B connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Nissan|Leaf 2018-23|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Nissan A connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Ram|1500 2019-23|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Ram connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Ascent 2019-21|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Forester 2019-21|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Impreza 2017-19|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|Impreza 2020-22|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Ram|1500 2019-24|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Ram connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Ascent 2019-21|All[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Subaru|Forester 2019-21|All[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Subaru|Impreza 2017-19|EyeSight Driver Assistance[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Subaru|Impreza 2020-22|EyeSight Driver Assistance[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| |Subaru|Legacy 2020-22|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| |Subaru|Outback 2020-22|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru B connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|XV 2018-19|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Subaru|XV 2020-21|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| -|Škoda|Fabia 2022-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Škoda|Kamiq 2021-23[9,11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Škoda|Karoq 2019-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Kodiaq 2017-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia 2015-19[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia RS 2016[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Scala 2020-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Škoda|Superb 2015-22[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|XV 2018-19|EyeSight Driver Assistance[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Subaru|XV 2020-21|EyeSight Driver Assistance[7](#footnotes)|openpilot available[1,8](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
Tools- 1 Pry Tool
- 1 Socket Wrench 8mm or 5/16" (deep)
|| +|Škoda|Fabia 2022-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Škoda|Kamiq 2021-23[10,12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Škoda|Karoq 2019-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Kodiaq 2017-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Octavia 2015-19[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Octavia RS 2016[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Scala 2020-23[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Škoda|Superb 2015-22[12](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -207,11 +216,11 @@ A supported vehicle is one that just works when you install a comma device. All |Toyota|Avalon Hybrid 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|C-HR 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|C-HR 2021|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|C-HR 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|C-HR Hybrid 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|C-HR Hybrid 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry 2018-20|All|Stock|0 mph[8](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry 2021-24|All|openpilot|0 mph[8](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|C-HR Hybrid 2021-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|Camry 2018-20|All|Stock|0 mph[9](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|Camry 2021-24|All|openpilot|0 mph[9](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Camry Hybrid 2021-24|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -235,47 +244,49 @@ A supported vehicle is one that just works when you install a comma device. All |Toyota|RAV4 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|RAV4 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|RAV4 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|RAV4 2023-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|RAV4 Hybrid 2017-18|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|RAV4 Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|RAV4 Hybrid 2023-24|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Sienna 2018-20|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 RJ45 cable (7 ft)
- 1 Toyota A connector
- 1 comma 3X
- 1 comma power v2
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon eHybrid 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon R 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Atlas Cross Sport 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|California 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Crafter 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|e-Crafter 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Grand California 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta GLI 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat 2015-22[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Volkswagen|T-Roc 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| -|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Tiguan 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Arteon 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Arteon eHybrid 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Arteon R 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Atlas Cross Sport 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|California 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Crafter 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|e-Crafter 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Grand California 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Jetta 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Jetta GLI 2021-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Passat 2015-22[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Volkswagen|T-Roc 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[14](#footnotes)|| +|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Tiguan 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,13](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 J533 connector
- 1 USB-C coupler
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| ### Footnotes 1openpilot Longitudinal Control (Alpha) is available behind a toggle; the toggle is only available in non-release branches such as `devel` or `master-ci`.
@@ -285,12 +296,13 @@ A supported vehicle is one that just works when you install a comma device. All 52019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
6Requires a CAN FD panda kit if not using comma 3X for this CAN FD car.
7In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.
-8openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
-9Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
-10Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
-11Some Škoda vehicles are equipped with heated windshields, which are known to block GPS signal needed for some comma 3X functionality.
-12Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC.
-13Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store.
+8Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.
+9openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
+10Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
+11Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
+12Some Škoda vehicles are equipped with heated windshields, which are known to block GPS signal needed for some comma 3X functionality.
+13Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC.
+14Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store.
## Community Maintained Cars Although they're not upstream, the community has openpilot running on other makes and models. See the 'Community Supported Models' section of each make [on our wiki](https://wiki.comma.ai/). diff --git a/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index 7a074f12de..30f4e0dfd3 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -1,26 +1,50 @@ # How to contribute -Our software is open source so you can solve your own problems without needing help from others. And if you solve a problem and are so kind, you can upstream it for the rest of the world to use. Check out our [post about externalization](https://blog.comma.ai/a-2020-theme-externalization/). - -Most open source development activity is coordinated through our [GitHub Discussions](https://github.com/commaai/openpilot/discussions) and [Discord](https://discord.comma.ai). A lot of documentation is available at https://docs.comma.ai and on our [blog](https://blog.comma.ai/). +Our software is open source so you can solve your own problems without needing help from others. And if you solve a problem and are so kind, you can upstream it for the rest of the world to use. Check out our [post about externalization](https://blog.comma.ai/a-2020-theme-externalization/). Development activity is coordinated through our GitHub Issues, [GitHub Discussions](https://github.com/commaai/openpilot/discussions), and [Discord](https://discord.comma.ai). ### Getting Started - * Setup your [development environment](../tools/) - * Join our [Discord](https://discord.comma.ai) - * Make sure you have a [GitHub account](https://github.com/signup/free) - * Fork [our repositories](https://github.com/commaai) on GitHub +* Setup your [development environment](../tools/) +* Read about the [development workflow](WORKFLOW.md) +* Join our [Discord](https://discord.comma.ai) +* Docs are at https://docs.comma.ai and https://blog.comma.ai + +## What contributions are we looking for? + +**openpilot's priorities are [safety](SAFETY.md), stability, quality, and features, in that order.** openpilot is part of comma's mission to *solve self-driving cars while delivering shippable intermediaries*, and **all** development is towards that goal. + +### What gets merged? + +The probability of a pull request being merged is a function of its value to the project and the effort it will take us to get it merged. +If a PR offers *some* value but will take lots of time to get merged, it will be closed. +Simple, well-tested bug fixes are the easiest to merge, and new features are the hardest to get merged. + +All of these are examples of good PRs: +* typo fix: https://github.com/commaai/openpilot/pull/30678 +* removing unused code: https://github.com/commaai/openpilot/pull/30573 +* simple car model port: https://github.com/commaai/openpilot/pull/30245 +* car brand port: https://github.com/commaai/openpilot/pull/23331 + +### What doesn't get merged? + +* **arbitrary style changes**: code is art, and it's up to the author to make it beautiful +* **500+ line PRs**: clean it up, break it up into smaller PRs, or both +* **PRs without a clear goal**: every PR must have a singular and clear goal +* **UI design changes**: we do not have a good review process for this yet +* **New features**: We believe openpilot is mostly feature-complete, and the rest is a matter of refinement and fixing bugs. As a result of this, most feature PRs will be immediately closed, however the beauty of open source is that forks can and do offer features that upstream openpilot doesn't. ### First contribution -Try out some of these first pull requests ideas to dive into the codebase: -* Increase our [mypy](http://mypy-lang.org/) coverage -* Write some documentation -* Tackle an open [good first issue](https://github.com/commaai/openpilot/issues?q=is%3Aissue+is%3Aopen+label%3A%22good+first+issue%22) +Check out any [good first issue](https://github.com/commaai/openpilot/issues?q=is%3Aissue+is%3Aopen+label%3A%22good+first+issue%22) to get started. + +### What do I need to contribute? + +A lot of openpilot work requires only a PC, and some requires a comma device. +Most car-related contributions require access to that car, plus a comma device installed in the car. ## Pull Requests -Pull requests should be against the master branch. Welcomed contributions include bug reports, car ports, and any [open issue](https://github.com/commaai/openpilot/issues). If you're unsure about a contribution, feel free to open a discussion, issue, or draft PR to discuss the problem you're trying to solve. +Pull requests should be against the master branch. If you're unsure about a contribution, feel free to open a discussion, issue, or draft PR to discuss the problem you're trying to solve. A good pull request has all of the following: * a clearly stated purpose @@ -31,18 +55,11 @@ A good pull request has all of the following: * if you've improved your car's tuning, post before and after plots * passes the CI tests -### Car Ports - -We've released a [Model Port guide](https://blog.comma.ai/openpilot-port-guide-for-toyota-models/) for porting to Toyota/Lexus models. - -If you port openpilot to a substantially new car brand, see this more generic [Brand Port guide](https://blog.comma.ai/how-to-write-a-car-port-for-openpilot/). - -## Testing - -### Automated Testing - -All PRs and commits are automatically checked by GitHub Actions. Check out `.github/workflows/` for what GitHub Actions runs. Any new tests should be added to GitHub Actions. - -### Code Style and Linting +## Contributing without Code -Code is automatically checked for style by GitHub Actions as part of the automated tests. You can also run these tests yourself by running `pre-commit run --all`. +* Report bugs in GitHub issues. +* Report driving issues in the `#driving-feedback` Discord channel. +* Consider opting into driver camera uploads to improve the driver monitoring model. +* Connect your device to Wi-Fi regularly, so that we can pull data for training better driving models. +* Run the `nightly` branch and report issues. This branch is like `master` but it's built just like a release. +* Annotate images in the [comma10k dateset](https://github.com/commaai/comma10k). diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 9fe9b1bd15..a7f61411c8 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -9,17 +9,17 @@ source "$BASEDIR/launch_env.sh" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" function agnos_init { - # wait longer for weston to come up - if [ -f "$BASEDIR/prebuilt" ]; then - sleep 3 - fi - # TODO: move this to agnos sudo rm -f /data/etc/NetworkManager/system-connections/*.nmmeta # set success flag for current boot slot sudo abctl --set_success + # TODO: do this without udev in AGNOS + # udev does this, but sometimes we startup faster + sudo chgrp gpu /dev/adsprpc-smd /dev/ion /dev/kgsl-3d0 + sudo chmod 660 /dev/adsprpc-smd /dev/ion /dev/kgsl-3d0 + # Check if AGNOS update is required if [ $(< /VERSION) != "$AGNOS_VERSION" ]; then AGNOS_PY="$DIR/system/hardware/tici/agnos.py" @@ -35,9 +35,6 @@ function launch { # Remove orphaned git lock if it exists on boot [ -f "$DIR/.git/index.lock" ] && rm -f $DIR/.git/index.lock - # Pull time from panda - $DIR/selfdrive/boardd/set_time.py - # Check to see if there's a valid overlay-based update available. Conditions # are as follows: # @@ -77,14 +74,19 @@ function launch { export PYTHONPATH="$PWD" # hardware specific init - agnos_init + if [ -f /AGNOS ]; then + agnos_init + fi # write tmux scrollback to a file tmux capture-pane -pq -S-1000 > /tmp/launch_log # start manager cd selfdrive/manager - ./build.py && ./manager.py + if [ ! -f $DIR/prebuilt ]; then + ./build.py + fi + ./manager.py # if broken, keep on screen error while true; do sleep 1; done diff --git a/launch_env.sh b/launch_env.sh index d07fbe33de..6859afb0d4 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,11 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="8.2" -fi - -if [ -z "$PASSIVE" ]; then - export PASSIVE="1" + export AGNOS_VERSION="9.7" fi export STAGING_ROOT="/data/safe_staging" diff --git a/launch_openpilot.sh b/launch_openpilot.sh index 1525e1715f..2888814c22 100755 --- a/launch_openpilot.sh +++ b/launch_openpilot.sh @@ -1,5 +1,3 @@ #!/usr/bin/bash -export PASSIVE="0" exec ./launch_chffrplus.sh - diff --git a/opendbc/can/common.h b/opendbc/can/common.h index 03b99e5598..cfc63eb105 100644 --- a/opendbc/can/common.h +++ b/opendbc/can/common.h @@ -54,7 +54,7 @@ public: bool ignore_checksum = false; bool ignore_counter = false; - bool parse(uint64_t sec, const std::vector &dat); + bool parse(uint64_t nanos, const std::vector &dat); bool update_counter_generic(int64_t v, int cnt_size); }; @@ -69,9 +69,9 @@ private: public: bool can_valid = false; bool bus_timeout = false; - uint64_t first_sec = 0; - uint64_t last_sec = 0; - uint64_t last_nonempty_sec = 0; + uint64_t first_nanos = 0; + uint64_t last_nanos = 0; + uint64_t last_nonempty_nanos = 0; uint64_t bus_timeout_threshold = 0; uint64_t can_invalid_cnt = CAN_INVALID_CNT; @@ -81,10 +81,10 @@ public: #ifndef DYNAMIC_CAPNP void update_string(const std::string &data, bool sendcan); void update_strings(const std::vector &data, std::vector &vals, bool sendcan); - void UpdateCans(uint64_t sec, const capnp::List::Reader& cans); + void UpdateCans(uint64_t nanos, const capnp::List::Reader& cans); #endif - void UpdateCans(uint64_t sec, const capnp::DynamicStruct::Reader& cans); - void UpdateValid(uint64_t sec); + void UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cans); + void UpdateValid(uint64_t nanos); void query_latest(std::vector &vals, uint64_t last_ts = 0); }; diff --git a/opendbc/can/common.pxd b/opendbc/can/common.pxd index 477f71b2d3..57053b781e 100644 --- a/opendbc/can/common.pxd +++ b/opendbc/can/common.pxd @@ -62,7 +62,7 @@ cdef extern from "common_dbc.h": cdef extern from "common.h": - cdef const DBC* dbc_lookup(const string) + cdef const DBC* dbc_lookup(const string) except + cdef cppclass CANParser: bool can_valid diff --git a/opendbc/can/packer_pyx.pyx b/opendbc/can/packer_pyx.pyx index 5133fcc990..1b9fc8fab6 100644 --- a/opendbc/can/packer_pyx.pyx +++ b/opendbc/can/packer_pyx.pyx @@ -26,6 +26,10 @@ cdef class CANPacker: msg = self.dbc[0].msgs[i] self.name_to_address[string(msg.name)] = msg.address + def __dealloc__(self): + if self.packer: + del self.packer + cdef vector[uint8_t] pack(self, addr, values): cdef vector[SignalPackValue] values_thing values_thing.reserve(len(values)) diff --git a/opendbc/can/parser.cc b/opendbc/can/parser.cc index bf2406ec3b..3ed9f02880 100644 --- a/opendbc/can/parser.cc +++ b/opendbc/can/parser.cc @@ -33,7 +33,11 @@ int64_t get_raw_value(const std::vector &msg, const Signal &sig) { } -bool MessageState::parse(uint64_t sec, const std::vector &dat) { +bool MessageState::parse(uint64_t nanos, const std::vector &dat) { + std::vector tmp_vals(parse_sigs.size()); + bool checksum_failed = false; + bool counter_failed = false; + for (int i = 0; i < parse_sigs.size(); i++) { const auto &sig = parse_sigs[i]; @@ -44,50 +48,48 @@ bool MessageState::parse(uint64_t sec, const std::vector &dat) { //DEBUG("parse 0x%X %s -> %ld\n", address, sig.name, tmp); - bool checksum_failed = false; if (!ignore_checksum) { if (sig.calc_checksum != nullptr && sig.calc_checksum(address, sig, dat) != tmp) { checksum_failed = true; } } - bool counter_failed = false; if (!ignore_counter) { - if (sig.type == SignalType::COUNTER) { - counter_failed = !update_counter_generic(tmp, sig.size); + if (sig.type == SignalType::COUNTER && !update_counter_generic(tmp, sig.size)) { + counter_failed = true; } } - if (checksum_failed || counter_failed) { - LOGE("0x%X message checks failed, checksum failed %d, counter failed %d", address, checksum_failed, counter_failed); - return false; - } + tmp_vals[i] = tmp * sig.factor + sig.offset; + } + + // only update values if both checksum and counter are valid + if (checksum_failed || counter_failed) { + LOGE("0x%X message checks failed, checksum failed %d, counter failed %d", address, checksum_failed, counter_failed); + return false; + } - // TODO: these may get updated if the invalid or checksum gets checked later - vals[i] = tmp * sig.factor + sig.offset; + for (int i = 0; i < parse_sigs.size(); i++) { + vals[i] = tmp_vals[i]; all_vals[i].push_back(vals[i]); } - last_seen_nanos = sec; + last_seen_nanos = nanos; return true; } bool MessageState::update_counter_generic(int64_t v, int cnt_size) { - uint8_t old_counter = counter; - counter = v; - if (((old_counter+1) & ((1 << cnt_size) -1)) != v) { - counter_fail += 1; + if (((counter + 1) & ((1 << cnt_size) -1)) != v) { + counter_fail = std::min(counter_fail + 1, MAX_BAD_COUNTER); if (counter_fail > 1) { - INFO("0x%X COUNTER FAIL #%d -- %d -> %d\n", address, counter_fail, old_counter, (int)v); - } - if (counter_fail >= MAX_BAD_COUNTER) { - return false; + INFO("0x%X COUNTER FAIL #%d -- %d -> %d\n", address, counter_fail, counter, (int)v); } } else if (counter_fail > 0) { counter_fail--; } - return true; + counter = v; + return counter_fail < MAX_BAD_COUNTER; } @@ -101,7 +103,7 @@ CANParser::CANParser(int abus, const std::string& dbc_name, const std::vector(); - if (first_sec == 0) { - first_sec = event.getLogMonoTime(); + if (first_nanos == 0) { + first_nanos = event.getLogMonoTime(); } - last_sec = event.getLogMonoTime(); + last_nanos = event.getLogMonoTime(); auto cans = sendcan ? event.getSendcan() : event.getCan(); - UpdateCans(last_sec, cans); + UpdateCans(last_nanos, cans); - UpdateValid(last_sec); + UpdateValid(last_nanos); } void CANParser::update_strings(const std::vector &data, std::vector &vals, bool sendcan) { - uint64_t current_sec = 0; + uint64_t current_nanos = 0; for (const auto &d : data) { update_string(d, sendcan); - if (current_sec == 0) { - current_sec = last_sec; + if (current_nanos == 0) { + current_nanos = last_nanos; } } - query_latest(vals, current_sec); + query_latest(vals, current_nanos); } -void CANParser::UpdateCans(uint64_t sec, const capnp::List::Reader& cans) { +void CANParser::UpdateCans(uint64_t nanos, const capnp::List::Reader& cans) { //DEBUG("got %d messages\n", cans.size()); bool bus_empty = true; @@ -238,18 +240,18 @@ void CANParser::UpdateCans(uint64_t sec, const capnp::List::Rea std::vector data(dat.size(), 0); memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(sec, data); + state_it->second.parse(nanos, data); } // update bus timeout if (!bus_empty) { - last_nonempty_sec = sec; + last_nonempty_nanos = nanos; } - bus_timeout = (sec - last_nonempty_sec) > bus_timeout_threshold; + bus_timeout = (nanos - last_nonempty_nanos) > bus_timeout_threshold; } #endif -void CANParser::UpdateCans(uint64_t sec, const capnp::DynamicStruct::Reader& cmsg) { +void CANParser::UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cmsg) { // assume message struct is `cereal::CanData` and parse assert(cmsg.has("address") && cmsg.has("src") && cmsg.has("dat") && cmsg.has("busTime")); @@ -268,11 +270,11 @@ void CANParser::UpdateCans(uint64_t sec, const capnp::DynamicStruct::Reader& cms if (dat.size() > 64) return; // shouldn't ever happen std::vector data(dat.size(), 0); memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(sec, data); + state_it->second.parse(nanos, data); } -void CANParser::UpdateValid(uint64_t sec) { - const bool show_missing = (last_sec - first_sec) > 8e9; +void CANParser::UpdateValid(uint64_t nanos) { + const bool show_missing = (last_nanos - first_nanos) > 8e9; bool _valid = true; bool _counters_valid = true; @@ -284,7 +286,7 @@ void CANParser::UpdateValid(uint64_t sec) { } const bool missing = state.last_seen_nanos == 0; - const bool timed_out = (sec - state.last_seen_nanos) > state.check_threshold; + const bool timed_out = (nanos - state.last_seen_nanos) > state.check_threshold; if (state.check_threshold > 0 && (missing || timed_out)) { if (show_missing && !bus_timeout) { if (missing) { @@ -302,7 +304,7 @@ void CANParser::UpdateValid(uint64_t sec) { void CANParser::query_latest(std::vector &vals, uint64_t last_ts) { if (last_ts == 0) { - last_ts = last_sec; + last_ts = last_nanos; } for (auto& kv : message_states) { auto& state = kv.second; diff --git a/opendbc/can/parser_pyx.pyx b/opendbc/can/parser_pyx.pyx index 808610e87a..8ce67740b0 100644 --- a/opendbc/can/parser_pyx.pyx +++ b/opendbc/can/parser_pyx.pyx @@ -66,6 +66,10 @@ cdef class CANParser: self.can = new cpp_CANParser(bus, dbc_name, message_v) self.update_strings([]) + def __dealloc__(self): + if self.can: + del self.can + def update_strings(self, strings, sendcan=False): for v in self.vl_all.values(): for l in v.values(): # no-cython-lint diff --git a/opendbc/chrysler_pacifica_2017_hybrid_generated.dbc b/opendbc/chrysler_pacifica_2017_hybrid_generated.dbc index 3036bc7284..d8f4c6623e 100644 --- a/opendbc/chrysler_pacifica_2017_hybrid_generated.dbc +++ b/opendbc/chrysler_pacifica_2017_hybrid_generated.dbc @@ -22,18 +22,47 @@ BO_ 280 ECM_TRQ: 8 XXX BO_ 284 ESP_8: 8 XXX SG_ BRK_PRESSURE : 3|12@0+ (1,0) [0|1] "" XXX + SG_ Vehicle_Stopped : 7|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_PEDAL : 19|12@0+ (1,0) [0|1] "" XXX SG_ Vehicle_Speed : 39|16@0+ (0.0078125,0) [0|511.984375] "km/h" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 288 ECM_2: 7 XXX + SG_ ACC_TORQUE_REQ_ENABLE : 5|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_ENABLE : 6|1@1+ (1,0) [0|0] "" XXX + SG_ TCM_TORQUE_REQ_ENABLE : 7|1@1+ (1,0) [0|0] "" XXX + SG_ Accelerator_Position : 16|8@1+ (0.4,0) [0|100] "%" XXX + SG_ CRUISE_OVERRIDE : 31|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 47|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|0] "" XXX + BO_ 320 ESP_1: 8 XXX + SG_ Brake_State : 0|2@1+ (1,0) [0|0] "" XXX SG_ Brake_Pedal_State : 2|2@1+ (1,0) [0|0] "" XXX + SG_ ACC_Engaged : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Enabled : 23|1@0+ (1,0) [0|1] "" XXX SG_ Vehicle_Speed : 33|10@0+ (0.5,0) [0|511] "km/h" XXX + SG_ ACC_OFF_REQ : 39|2@0+ (1,0) [0|0] "" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ BRAKE_PRESSED_ACC : 6|1@0+ (1,0) [0|3] "" XXX +BO_ 268 ESP_2: 8 ESC + SG_ ESC_TORQUE_REQ : 4|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ ACC_TORQUE_REQ_ENABLE : 5|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_MAX : 6|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_MIN : 7|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_TORQUE_REQ : 20|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ TCS_ACTIVE : 21|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_TORQUE_REQ_MAX : 22|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_BRK_PREP : 40|1@1+ (1,0) [0|0] "" XXX + SG_ DISABLE_FUEL_SHUTOFF : 47|1@1+ (1,0) [0|0] "" XXX + SG_ DAS_REQ_ACTIVE : 48|3@1+ (1,0) [0|0] "" XXX + SG_ COLLISION_BRK_PREP : 51|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX + BO_ 344 ESP_6: 8 XXX SG_ WHEEL_SPEED_FL : 5|14@0+ (0.5,0) [0|8191] "rpm" XXX SG_ WHEEL_SPEED_FR : 21|14@0+ (0.5,0) [0|8191] "rpm" XXX @@ -59,11 +88,9 @@ BO_ 500 DAS_3: 8 XXX SG_ DISABLE_FUEL_SHUTOFF : 23|1@1+ (1,0) [0|0] "" XXX SG_ GR_MAX_REQ : 32|4@1+ (1,0) [0|0] "" XXX SG_ ACC_DECEL_REQ : 36|3@1+ (1,0) [0|0] "" XXX - SG_ STS : 46|2@1+ (1,0) [0|0] "" XXX - SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_FAULTED : 46|2@1+ (1,0) [0|0] "" XXX SG_ COLLISION_BRK_PREP : 48|1@1+ (1,0) [0|0] "" XXX SG_ ACC_BRK_PREP : 49|1@1+ (1,0) [0|0] "" XXX - SG_ BRAKE_BOOL_1 : 36|1@0+ (1,0) [0|3] "" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX @@ -74,6 +101,11 @@ BO_ 501 DAS_4: 8 XXX SG_ ACC_DISTANCE_CONFIG_2 : 41|2@0+ (1,0) [0|3] "" XXX SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX SG_ ACC_STATE : 38|3@0+ (1,0) [0|7] "" XXX + SG_ FCW_OFF : 25|2@0+ (1,0) [0|3] "" XXX + SG_ FCW_ERROR : 27|2@0+ (1,0) [0|3] "" XXX + SG_ FCW_BRAKE_ENABLED : 29|1@0+ (1,0) [0|1] "" XXX + SG_ FCW_BRAKE_DISABLED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_FAULTED : 50|1@0+ (1,0) [0|1] "" XXX BO_ 544 EPS_2: 8 XXX SG_ LKAS_STATE : 23|4@0+ (1,0) [0|15] "" XXX @@ -103,12 +135,28 @@ BO_ 571 CRUISE_BUTTONS: 3 XXX SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 23|8@0+ (1,0) [0|255] "" XXX +BO_ 625 DAS_5: 8 XXX + SG_ FCW_STATE : 2|1@1+ (1,0) [0|0] "" XXX + SG_ FCW_DISTANCE : 3|2@1+ (1,0) [0|0] "" XXX + SG_ ACCFCW_MESSAGE : 12|4@1+ (1,0) [0|0] "" XXX + SG_ SET_SPEED_KPH : 24|8@1+ (1,0) [0|250] "km/h" XXX + SG_ WHEEL_TORQUE_REQUEST : 38|15@0+ (1,-7767) [-7767|24999] "Nm" XXX + SG_ WHEEL_TORQUE_REQUEST_ACTIVE : 39|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 669 EPB_1: 3 XXX + SG_ PARKING_BRAKE_STATUS : 11|3@0+ (1,0) [0|7] "" XXX + SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 23|8@0+ (1,0) [0|255] "" XXX + BO_ 678 DAS_6: 8 XXX SG_ LKAS_ICON_COLOR : 1|2@0+ (1,0) [0|3] "" XXX SG_ LKAS_LANE_LINES : 19|4@0+ (1,0) [0|1] "" XXX SG_ LKAS_ALERTS : 27|4@0+ (1,0) [0|1] "" XXX SG_ CAR_MODEL : 15|8@0+ (1,0) [0|255] "" XXX SG_ AUTO_HIGH_BEAM_ON : 47|1@1+ (1,0) [0|0] "" XXX + SG_ LKAS_DISABLED : 56|1@1+ (1,0) [0|0] "" XXX BO_ 720 BSM_1: 6 XXX SG_ RIGHT_STATUS : 5|1@0+ (1,0) [0|1] "" XXX @@ -124,11 +172,14 @@ BO_ 820 BCM_1: 8 XXX SG_ DOOR_OPEN_RL : 19|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_RR : 20|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_TRUNK : 22|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE_SWITCH : 23|1@0+ (1,0) [0|1] "" XXX SG_ TURN_LIGHT_LEFT : 31|1@0+ (1,0) [0|1] "" XXX SG_ TURN_LIGHT_RIGHT : 30|1@0+ (1,0) [0|1] "" XXX SG_ HIGH_BEAM_DISPLAY : 58|1@0+ (1,0) [0|1] "" XXX +VAL_ 320 ACC_OFF_REQ 2 "PERMANENT" 1 "TEMPORARY" 0 "NONE" VAL_ 368 Gear_State 4 "D" 2 "N" 1 "R" 0 "P" ; +VAL_ 669 PARKING_BRAKE_STATUS 3 "RELEASING" 2 "APPLYING" 1 "APPLIED" 0 "OFF" ; CM_ SG_ 258 STEERING_ANGLE_HP "Steering angle high precision"; CM_ SG_ 264 ENGINE_TORQUE "Effective engine torque"; @@ -209,12 +260,6 @@ BO_ 608 PARKSENSE_SIGNAL: 8 XXX BO_ 729 LKAS_HEARTBIT: 5 XXX SG_ LKAS_STATUS_OK : 31|16@0+ (1,0) [0|65535] "" XXX -BO_ 288 ACCEL_RELATED_120: 7 XXX - SG_ COUNTER : 47|4@0+ (1,0) [0|15] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL : 23|8@0+ (1,0) [0|255] "" XXX - SG_ GAS_ENGINE_RPM_MAYBE : 31|16@0+ (1,0) [0|65535] "" XXX - BO_ 257 ACCEL_RELATED_101: 5 XXX SG_ ENERGY_OR_RPM : 31|8@0+ (1,0) [0|255] "" XXX @@ -278,17 +323,6 @@ BO_ 324 SPEED_2: 8 XXX BO_ 832 UNKNOWN_340: 8 XXX SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX -BO_ 625 ACC_1: 8 XXX - SG_ SPEED : 31|8@0+ (1,0) [0|255] "km/h" XXX - SG_ ACCEL_PERHAPS : 39|16@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX - -BO_ 268 ACC_10c: 8 XXX - SG_ BRAKE_PERHAPS : 48|1@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - CM_ SG_ 653 BRAKE_PRESSURE "max seems to be 148"; CM_ SG_ 746 PRNDL "5=L, 4=D, 3=N, 2=R, 1=P"; CM_ SG_ 320 BRAKE_PRESSED_2 "Value is 5 when brake is pressed by human, 1 when ACC brake"; diff --git a/opendbc/chrysler_ram_dt_generated.dbc b/opendbc/chrysler_ram_dt_generated.dbc index 2eb5aecf39..b502c15bee 100644 --- a/opendbc/chrysler_ram_dt_generated.dbc +++ b/opendbc/chrysler_ram_dt_generated.dbc @@ -24,18 +24,47 @@ BO_ 181 ECM_TRQ: 8 XXX BO_ 121 ESP_8: 8 XXX SG_ BRK_PRESSURE : 3|12@0+ (1,0) [0|1] "" XXX + SG_ Vehicle_Stopped : 7|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_PEDAL : 19|12@0+ (1,0) [0|1] "" XXX SG_ Vehicle_Speed : 39|16@0+ (0.0078125,0) [0|511.984375] "km/h" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 123 ECM_2: 7 XXX + SG_ ACC_TORQUE_REQ_ENABLE : 5|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_ENABLE : 6|1@1+ (1,0) [0|0] "" XXX + SG_ TCM_TORQUE_REQ_ENABLE : 7|1@1+ (1,0) [0|0] "" XXX + SG_ Accelerator_Position : 16|8@1+ (0.4,0) [0|100] "%" XXX + SG_ CRUISE_OVERRIDE : 31|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 47|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|0] "" XXX + BO_ 131 ESP_1: 8 XXX + SG_ Brake_State : 0|2@1+ (1,0) [0|0] "" XXX SG_ Brake_Pedal_State : 2|2@1+ (1,0) [0|0] "" XXX + SG_ ACC_Engaged : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Enabled : 23|1@0+ (1,0) [0|1] "" XXX SG_ Vehicle_Speed : 33|10@0+ (0.5,0) [0|511] "km/h" XXX + SG_ ACC_OFF_REQ : 39|2@0+ (1,0) [0|0] "" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ BRAKE_PRESSED_ACC : 6|1@0+ (1,0) [0|3] "" XXX +BO_ 113 ESP_2: 8 ESC + SG_ ESC_TORQUE_REQ : 4|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ ACC_TORQUE_REQ_ENABLE : 5|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_MAX : 6|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_MIN : 7|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_TORQUE_REQ : 20|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ TCS_ACTIVE : 21|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_TORQUE_REQ_MAX : 22|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_BRK_PREP : 40|1@1+ (1,0) [0|0] "" XXX + SG_ DISABLE_FUEL_SHUTOFF : 47|1@1+ (1,0) [0|0] "" XXX + SG_ DAS_REQ_ACTIVE : 48|3@1+ (1,0) [0|0] "" XXX + SG_ COLLISION_BRK_PREP : 51|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX + BO_ 139 ESP_6: 8 XXX SG_ WHEEL_SPEED_FL : 5|14@0+ (0.5,0) [0|8191] "rpm" XXX SG_ WHEEL_SPEED_FR : 21|14@0+ (0.5,0) [0|8191] "rpm" XXX @@ -61,11 +90,9 @@ BO_ 153 DAS_3: 8 XXX SG_ DISABLE_FUEL_SHUTOFF : 23|1@1+ (1,0) [0|0] "" XXX SG_ GR_MAX_REQ : 32|4@1+ (1,0) [0|0] "" XXX SG_ ACC_DECEL_REQ : 36|3@1+ (1,0) [0|0] "" XXX - SG_ STS : 46|2@1+ (1,0) [0|0] "" XXX - SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_FAULTED : 46|2@1+ (1,0) [0|0] "" XXX SG_ COLLISION_BRK_PREP : 48|1@1+ (1,0) [0|0] "" XXX SG_ ACC_BRK_PREP : 49|1@1+ (1,0) [0|0] "" XXX - SG_ BRAKE_BOOL_1 : 36|1@0+ (1,0) [0|3] "" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX @@ -76,6 +103,11 @@ BO_ 232 DAS_4: 8 XXX SG_ ACC_DISTANCE_CONFIG_2 : 41|2@0+ (1,0) [0|3] "" XXX SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX SG_ ACC_STATE : 38|3@0+ (1,0) [0|7] "" XXX + SG_ FCW_OFF : 25|2@0+ (1,0) [0|3] "" XXX + SG_ FCW_ERROR : 27|2@0+ (1,0) [0|3] "" XXX + SG_ FCW_BRAKE_ENABLED : 29|1@0+ (1,0) [0|1] "" XXX + SG_ FCW_BRAKE_DISABLED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_FAULTED : 50|1@0+ (1,0) [0|1] "" XXX BO_ 49 EPS_2: 8 XXX SG_ LKAS_STATE : 23|4@0+ (1,0) [0|15] "" XXX @@ -105,12 +137,28 @@ BO_ 177 CRUISE_BUTTONS: 3 XXX SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 23|8@0+ (1,0) [0|255] "" XXX +BO_ 163 DAS_5: 8 XXX + SG_ FCW_STATE : 2|1@1+ (1,0) [0|0] "" XXX + SG_ FCW_DISTANCE : 3|2@1+ (1,0) [0|0] "" XXX + SG_ ACCFCW_MESSAGE : 12|4@1+ (1,0) [0|0] "" XXX + SG_ SET_SPEED_KPH : 24|8@1+ (1,0) [0|250] "km/h" XXX + SG_ WHEEL_TORQUE_REQUEST : 38|15@0+ (1,-7767) [-7767|24999] "Nm" XXX + SG_ WHEEL_TORQUE_REQUEST_ACTIVE : 39|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 213 EPB_1: 3 XXX + SG_ PARKING_BRAKE_STATUS : 11|3@0+ (1,0) [0|7] "" XXX + SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 23|8@0+ (1,0) [0|255] "" XXX + BO_ 250 DAS_6: 8 XXX SG_ LKAS_ICON_COLOR : 1|2@0+ (1,0) [0|3] "" XXX SG_ LKAS_LANE_LINES : 19|4@0+ (1,0) [0|1] "" XXX SG_ LKAS_ALERTS : 27|4@0+ (1,0) [0|1] "" XXX SG_ CAR_MODEL : 15|8@0+ (1,0) [0|255] "" XXX SG_ AUTO_HIGH_BEAM_ON : 47|1@1+ (1,0) [0|0] "" XXX + SG_ LKAS_DISABLED : 56|1@1+ (1,0) [0|0] "" XXX BO_ 720 BSM_1: 6 XXX SG_ RIGHT_STATUS : 5|1@0+ (1,0) [0|1] "" XXX @@ -126,11 +174,14 @@ BO_ 657 BCM_1: 8 XXX SG_ DOOR_OPEN_RL : 19|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_RR : 20|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_TRUNK : 22|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE_SWITCH : 23|1@0+ (1,0) [0|1] "" XXX SG_ TURN_LIGHT_LEFT : 31|1@0+ (1,0) [0|1] "" XXX SG_ TURN_LIGHT_RIGHT : 30|1@0+ (1,0) [0|1] "" XXX SG_ HIGH_BEAM_DISPLAY : 58|1@0+ (1,0) [0|1] "" XXX +VAL_ 131 ACC_OFF_REQ 2 "PERMANENT" 1 "TEMPORARY" 0 "NONE" VAL_ 147 Gear_State 4 "D" 2 "N" 1 "R" 0 "P" ; +VAL_ 213 PARKING_BRAKE_STATUS 3 "RELEASING" 2 "APPLYING" 1 "APPLIED" 0 "OFF" ; CM_ SG_ 258 STEERING_ANGLE_HP "Steering angle high precision"; CM_ SG_ 264 ENGINE_TORQUE "Effective engine torque"; @@ -148,10 +199,14 @@ BO_ 53 PCM_2: 8 XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX BO_ 133 TCM_1: 8 XXX - SG_ DESIRED_GEAR : 15|4@0+ (1,0) [0|1] "" XXX SG_ SHIFT_PENDING : 2|1@0+ (1,0) [0|1] "" XXX - SG_ SPEED_TURBINE : 27|12@0+ (0.04,0) [0|1] "km/h" XXX SG_ ACTUAL_GEAR : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DESIRED_GEAR : 15|4@0+ (1,0) [0|1] "" XXX + SG_ TC_LOCKED : 17|1@1+ (1,0) [0|0] "" XXX + SG_ OUTPUT_SPEED : 31|16@0+ (1,0) [0|65534] "rpm" XXX + SG_ INPUT_SPEED : 47|16@0+ (1,0) [0|65534] "rpm" XXX + SG_ OUTPUT_SPEED_SIGN : 57|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|4@0+ (1,0) [0|15] "" XXX BO_ 135 ABS_2: 8 XXX SG_ COUNTER : 55|4@0+ (1,0) [0|1] "" XXX diff --git a/opendbc/chrysler_ram_hd_generated.dbc b/opendbc/chrysler_ram_hd_generated.dbc index 82cf0d3656..697c3bf912 100644 --- a/opendbc/chrysler_ram_hd_generated.dbc +++ b/opendbc/chrysler_ram_hd_generated.dbc @@ -24,18 +24,47 @@ BO_ 280 ECM_TRQ: 8 XXX BO_ 284 ESP_8: 8 XXX SG_ BRK_PRESSURE : 3|12@0+ (1,0) [0|1] "" XXX + SG_ Vehicle_Stopped : 7|1@0+ (1,0) [0|1] "" XXX SG_ BRAKE_PEDAL : 19|12@0+ (1,0) [0|1] "" XXX SG_ Vehicle_Speed : 39|16@0+ (0.0078125,0) [0|511.984375] "km/h" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 288 ECM_2: 7 XXX + SG_ ACC_TORQUE_REQ_ENABLE : 5|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_ENABLE : 6|1@1+ (1,0) [0|0] "" XXX + SG_ TCM_TORQUE_REQ_ENABLE : 7|1@1+ (1,0) [0|0] "" XXX + SG_ Accelerator_Position : 16|8@1+ (0.4,0) [0|100] "%" XXX + SG_ CRUISE_OVERRIDE : 31|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 47|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|0] "" XXX + BO_ 320 ESP_1: 8 XXX + SG_ Brake_State : 0|2@1+ (1,0) [0|0] "" XXX SG_ Brake_Pedal_State : 2|2@1+ (1,0) [0|0] "" XXX + SG_ ACC_Engaged : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Enabled : 23|1@0+ (1,0) [0|1] "" XXX SG_ Vehicle_Speed : 33|10@0+ (0.5,0) [0|511] "km/h" XXX + SG_ ACC_OFF_REQ : 39|2@0+ (1,0) [0|0] "" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ BRAKE_PRESSED_ACC : 6|1@0+ (1,0) [0|3] "" XXX +BO_ 268 ESP_2: 8 ESC + SG_ ESC_TORQUE_REQ : 4|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ ACC_TORQUE_REQ_ENABLE : 5|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_MAX : 6|1@1+ (1,0) [0|0] "" XXX + SG_ ESC_TORQUE_REQ_MIN : 7|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_TORQUE_REQ : 20|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ TCS_ACTIVE : 21|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_TORQUE_REQ_MAX : 22|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_BRK_PREP : 40|1@1+ (1,0) [0|0] "" XXX + SG_ DISABLE_FUEL_SHUTOFF : 47|1@1+ (1,0) [0|0] "" XXX + SG_ DAS_REQ_ACTIVE : 48|3@1+ (1,0) [0|0] "" XXX + SG_ COLLISION_BRK_PREP : 51|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX + BO_ 344 ESP_6: 8 XXX SG_ WHEEL_SPEED_FL : 5|14@0+ (0.5,0) [0|8191] "rpm" XXX SG_ WHEEL_SPEED_FR : 21|14@0+ (0.5,0) [0|8191] "rpm" XXX @@ -61,11 +90,9 @@ BO_ 500 DAS_3: 8 XXX SG_ DISABLE_FUEL_SHUTOFF : 23|1@1+ (1,0) [0|0] "" XXX SG_ GR_MAX_REQ : 32|4@1+ (1,0) [0|0] "" XXX SG_ ACC_DECEL_REQ : 36|3@1+ (1,0) [0|0] "" XXX - SG_ STS : 46|2@1+ (1,0) [0|0] "" XXX - SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_FAULTED : 46|2@1+ (1,0) [0|0] "" XXX SG_ COLLISION_BRK_PREP : 48|1@1+ (1,0) [0|0] "" XXX SG_ ACC_BRK_PREP : 49|1@1+ (1,0) [0|0] "" XXX - SG_ BRAKE_BOOL_1 : 36|1@0+ (1,0) [0|3] "" XXX SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX @@ -76,6 +103,11 @@ BO_ 501 DAS_4: 8 XXX SG_ ACC_DISTANCE_CONFIG_2 : 41|2@0+ (1,0) [0|3] "" XXX SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX SG_ ACC_STATE : 38|3@0+ (1,0) [0|7] "" XXX + SG_ FCW_OFF : 25|2@0+ (1,0) [0|3] "" XXX + SG_ FCW_ERROR : 27|2@0+ (1,0) [0|3] "" XXX + SG_ FCW_BRAKE_ENABLED : 29|1@0+ (1,0) [0|1] "" XXX + SG_ FCW_BRAKE_DISABLED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_FAULTED : 50|1@0+ (1,0) [0|1] "" XXX BO_ 544 EPS_2: 8 XXX SG_ LKAS_STATE : 23|4@0+ (1,0) [0|15] "" XXX @@ -105,12 +137,28 @@ BO_ 570 CRUISE_BUTTONS: 3 XXX SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX SG_ CHECKSUM : 23|8@0+ (1,0) [0|255] "" XXX +BO_ 625 DAS_5: 8 XXX + SG_ FCW_STATE : 2|1@1+ (1,0) [0|0] "" XXX + SG_ FCW_DISTANCE : 3|2@1+ (1,0) [0|0] "" XXX + SG_ ACCFCW_MESSAGE : 12|4@1+ (1,0) [0|0] "" XXX + SG_ SET_SPEED_KPH : 24|8@1+ (1,0) [0|250] "km/h" XXX + SG_ WHEEL_TORQUE_REQUEST : 38|15@0+ (1,-7767) [-7767|24999] "Nm" XXX + SG_ WHEEL_TORQUE_REQUEST_ACTIVE : 39|1@1+ (1,0) [0|0] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 669 EPB_1: 3 XXX + SG_ PARKING_BRAKE_STATUS : 11|3@0+ (1,0) [0|7] "" XXX + SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 23|8@0+ (1,0) [0|255] "" XXX + BO_ 629 DAS_6: 8 XXX SG_ LKAS_ICON_COLOR : 1|2@0+ (1,0) [0|3] "" XXX SG_ LKAS_LANE_LINES : 19|4@0+ (1,0) [0|1] "" XXX SG_ LKAS_ALERTS : 27|4@0+ (1,0) [0|1] "" XXX SG_ CAR_MODEL : 15|8@0+ (1,0) [0|255] "" XXX SG_ AUTO_HIGH_BEAM_ON : 47|1@1+ (1,0) [0|0] "" XXX + SG_ LKAS_DISABLED : 56|1@1+ (1,0) [0|0] "" XXX BO_ 720 BSM_1: 6 XXX SG_ RIGHT_STATUS : 5|1@0+ (1,0) [0|1] "" XXX @@ -126,11 +174,14 @@ BO_ 820 BCM_1: 8 XXX SG_ DOOR_OPEN_RL : 19|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_RR : 20|1@0+ (1,0) [0|1] "" XXX SG_ DOOR_OPEN_TRUNK : 22|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE_SWITCH : 23|1@0+ (1,0) [0|1] "" XXX SG_ TURN_LIGHT_LEFT : 31|1@0+ (1,0) [0|1] "" XXX SG_ TURN_LIGHT_RIGHT : 30|1@0+ (1,0) [0|1] "" XXX SG_ HIGH_BEAM_DISPLAY : 58|1@0+ (1,0) [0|1] "" XXX +VAL_ 320 ACC_OFF_REQ 2 "PERMANENT" 1 "TEMPORARY" 0 "NONE" VAL_ 368 Gear_State 4 "D" 2 "N" 1 "R" 0 "P" ; +VAL_ 669 PARKING_BRAKE_STATUS 3 "RELEASING" 2 "APPLYING" 1 "APPLIED" 0 "OFF" ; CM_ SG_ 258 STEERING_ANGLE_HP "Steering angle high precision"; CM_ SG_ 264 ENGINE_TORQUE "Effective engine torque"; diff --git a/opendbc/gm_global_a_powertrain_generated.dbc b/opendbc/gm_global_a_powertrain_generated.dbc index 6ecb36f2fa..37ad918cb2 100644 --- a/opendbc/gm_global_a_powertrain_generated.dbc +++ b/opendbc/gm_global_a_powertrain_generated.dbc @@ -125,6 +125,10 @@ BO_ 320 BCMTurnSignals: 3 K9_BCM SG_ HighBeamsActive : 7|1@0+ (1,0) [0|1] "" XXX SG_ HighBeamsTemporary : 5|1@0+ (1,0) [0|1] "" XXX +BO_ 322 BCMBlindSpotMonitor: 7 K9_BCM + SG_ LeftBSM : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RightBSM : 7|1@0+ (1,0) [0|1] "" XXX + BO_ 328 PSCM_148: 1 K43_PSCM BO_ 381 ESPStatus: 6 K20_ECM @@ -244,12 +248,10 @@ BO_ 840 EBCMWheelSpdFront: 5 K17_EBCM SG_ FRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO BO_ 842 EBCMWheelSpdRear: 5 K17_EBCM - SG_ RLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO - SG_ RRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO - SG_ MovingForward : 32|1@0+ (1,0) [0|1] "" XXX - SG_ MovingBackward : 33|1@0+ (1,0) [0|1] "" XXX - SG_ MovingForward2 : 35|1@1+ (1,0) [0|1] "" XXX - SG_ MovingBackward2 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ RLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ RRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ RRWheelDir : 34|3@0+ (1,0) [0|7] "" NEO + SG_ RLWheelDir : 37|3@0+ (1,0) [0|7] "" NEO BO_ 869 ASCM_365: 4 K124_ASCM @@ -317,6 +319,8 @@ CM_ BU_ K124_ASCM "Active Safety Control Module"; CM_ SG_ 381 MSG17D_AccPower "Need to investigate"; CM_ BO_ 190 "Length varies from 6 to 8 bytes by car"; CM_ SG_ 190 GasPedalAndAcc "ACC baseline is 62"; +CM_ SG_ 322 LeftBSM "For some cars, this can only be when the blinker is also active"; +CM_ SG_ 322 RightBSM "For some cars, this can only be when the blinker is also active"; CM_ SG_ 352 ImmobilizerInfo "Non-zero when ignition or accessory mode"; CM_ SG_ 451 GasPedalAndAcc2 "ACC baseline is 62"; CM_ SG_ 481 ACCAlwaysOne "Usually 1 if the car is equipped with ACC"; @@ -347,6 +351,8 @@ VAL_ 452 CruiseState 4 "Standstill" 3 "Faulted" 1 "Active" 0 "Off" ; VAL_ 309 PRNDL 3 "R" 2 "D" 1 "N" 0 "P" ; VAL_ 309 ESPButton 1 "Active" 0 "Inactive" ; VAL_ 384 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 842 RRWheelDir 0 "Stationary" 1 "Forward" 2 "Reverse" 3 "Unsupported" 4 "Fault"; +VAL_ 842 RLWheelDir 0 "Stationary" 1 "Forward" 2 "Reverse" 3 "Unsupported" 4 "Fault"; VAL_ 880 ACCCruiseState 2 "Adaptive" 3 "Adaptive" 4 "Non-adaptive" 5 "Non-adaptive" ; VAL_ 880 ACCLeadCar 1 "Present" 0 "Not Present" ; VAL_ 880 ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; diff --git a/opendbc/honda_civic_touring_2016_can_generated.dbc b/opendbc/honda_civic_touring_2016_can_generated.dbc index 47205cb24c..82271c417e 100644 --- a/opendbc/honda_civic_touring_2016_can_generated.dbc +++ b/opendbc/honda_civic_touring_2016_can_generated.dbc @@ -374,10 +374,9 @@ BO_ 1302 ODOMETER: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 450 EPB_STATE "3 \"engaged\" 2 \"disengaging\" 1 \"engaging\" 0 \"disengaged\""; CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 399 STEER_STATUS 7 "permanent_fault" 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; diff --git a/opendbc/hyundai_kia_generic.dbc b/opendbc/hyundai_kia_generic.dbc index 3031c4bc22..fc4d14f4fe 100644 --- a/opendbc/hyundai_kia_generic.dbc +++ b/opendbc/hyundai_kia_generic.dbc @@ -109,6 +109,10 @@ BO_ 1265 CLU11: 4 CLU SG_ CF_Clu_AmpInfo : 25|1@1+ (1.0,0.0) [0.0|1.0] "" BCM SG_ CF_Clu_AliveCnt1 : 28|4@1+ (1.0,0.0) [0.0|15.0] "" AHLS,EMS,EPB,LDWS_LKAS,MDPS,SCC +BO_ 1260 Sign_Detection: 8 XXX + SG_ SpeedLim_Nav_Cam : 40|8@1+ (1,0) [0|255] "km/h / mph" XXX + SG_ SpeedLim_Nav_Cam2 : 48|8@1+ (1,0) [0|255] "km/h / mph" XXX + BO_ 1492 TMU_GW_PE_01: 8 CLU SG_ TMU_IVRActivity : 0|2@1+ (1.0,0.0) [0.0|3.0] "" DATC SG_ TMU_PhoneActivity : 2|2@1+ (1.0,0.0) [0.0|3.0] "" DATC diff --git a/opendbc/subaru_global_2017_generated.dbc b/opendbc/subaru_global_2017_generated.dbc index 319764fc9b..9732feae15 100644 --- a/opendbc/subaru_global_2017_generated.dbc +++ b/opendbc/subaru_global_2017_generated.dbc @@ -279,6 +279,7 @@ BO_ 289 ES_STATIC_2: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX SG_ SET_3 : 15|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_Fault : 18|1@0+ (1,0) [0|1] "" XXX CM_ SG_ 64 Throttle_Combo "Throttle Cruise + Pedal"; CM_ SG_ 313 Brake_Lights "Driver or Cruise Brake on"; @@ -322,8 +323,8 @@ BO_ 545 ES_Distance: 8 XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX SG_ Signal1 : 12|3@1+ (1,0) [0|7] "" XXX SG_ Cruise_Fault : 15|1@1+ (1,0) [0|1] "" XXX - SG_ Cruise_Throttle : 16|12@1+ (1,0) [0|4095] "" XXX - SG_ Signal2 : 28|4@1+ (1,0) [0|15] "" XXX + SG_ Cruise_Throttle : 16|13@1+ (1,0) [0|4095] "" XXX + SG_ Signal2 : 29|3@1+ (1,0) [0|15] "" XXX SG_ Car_Follow : 32|1@1+ (1,0) [0|1] "" XXX SG_ Low_Speed_Follow : 33|1@1+ (1,0) [0|1] "" XXX SG_ Cruise_Soft_Disable : 34|1@1+ (1,0) [0|1] "" XXX @@ -344,8 +345,7 @@ BO_ 546 ES_Status: 8 XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX SG_ Signal1 : 12|3@1+ (1,0) [0|1] "" XXX SG_ Cruise_Fault : 15|1@1+ (1,0) [0|1] "" XXX - SG_ Cruise_RPM : 16|12@1+ (1,0) [0|4095] "" XXX - SG_ Signal2 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ Cruise_RPM : 16|13@1+ (1,0) [0|4095] "" XXX SG_ Cruise_Activated : 29|1@0+ (1,0) [0|1] "" XXX SG_ Brake_Lights : 30|1@1+ (1,0) [0|1] "" XXX SG_ Cruise_Hold : 31|1@1+ (1,0) [0|1] "" XXX diff --git a/opendbc/subaru_global_2020_hybrid_generated.dbc b/opendbc/subaru_global_2020_hybrid_generated.dbc index 99087eb228..c41eaf9965 100644 --- a/opendbc/subaru_global_2020_hybrid_generated.dbc +++ b/opendbc/subaru_global_2020_hybrid_generated.dbc @@ -279,6 +279,7 @@ BO_ 289 ES_STATIC_2: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX SG_ SET_3 : 15|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_Fault : 18|1@0+ (1,0) [0|1] "" XXX CM_ SG_ 64 Throttle_Combo "Throttle Cruise + Pedal"; CM_ SG_ 313 Brake_Lights "Driver or Cruise Brake on"; diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc/toyota_nodsu_pt_generated.dbc index c03949164c..7538b46a72 100644 --- a/opendbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc/toyota_nodsu_pt_generated.dbc @@ -562,7 +562,7 @@ BO_ 401 STEERING_LTA: 8 XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ TORQUE_WIND_DOWN : 47|8@0+ (1,0) [0|255] "" XXX SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX SG_ STEER_REQUEST_2 : 25|1@0+ (1,0) [0|1] "" XXX @@ -603,7 +603,7 @@ BO_ 1014 BSM: 8 XXX SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX CM_ SG_ 401 PERCENTAGE "driver override percentage (0-100), very close to steeringPressed in OP"; -CM_ SG_ 401 SETME_X64 "ramps to 0 smoothly then back on falling edge of STEER_REQUEST if BIT isn't 1"; +CM_ SG_ 401 TORQUE_WIND_DOWN "used to wind down torque on user override"; CM_ SG_ 401 ANGLE "angle of car relative to lane center on LTA camera"; CM_ SG_ 401 STEER_ANGLE_CMD "desired angle, OEM steers up to 95 degrees, no angle limit but torque will bottom out"; CM_ SG_ 401 CLEAR_HOLD_STEERING_ALERT "set to 1 when user clears LKAS_HUD->LDA_ALERT ('Hold Steering') by applying torque to steering wheel"; diff --git a/opendbc/vw_golf_mk4.dbc b/opendbc/vw_golf_mk4.dbc index 131a4b763c..6f14789135 100644 --- a/opendbc/vw_golf_mk4.dbc +++ b/opendbc/vw_golf_mk4.dbc @@ -1518,8 +1518,15 @@ CM_ SG_ 912 BSK_HD_Hauptraste "Status of trunk lid main detent"; CM_ SG_ 1088 Zaehler_Getriebe_1 "Counter Getriebe_1"; CM_ SG_ 1088 Waehlhebelposition__Getriebe_1_ "Gear Selector Position"; CM_ SG_ 1088 inneres_Soll_Motormoment "Desired Inner Torque"; +CM_ SG_ 1088 Gang_eingelegt "Gear Engaged"; CM_ SG_ 1088 Schaltabsicht "Shift Intent"; +CM_ SG_ 1088 Kuehlleistung "Cooling Power"; CM_ SG_ 1088 Wandlerverlustmoment "Converter Torque Loss"; +CM_ SG_ 1088 Getriebe_Notlauf "Transmission_Notlauf"; +CM_ SG_ 1088 Zielgang_oder_eingelegter_Gang "target_gear_or_gear_in_engagement"; +CM_ SG_ 1088 Uebertragungsfunktion "transfer function"; +CM_ SG_ 1088 EGS_Anforderung "EGS Requirement"; +CM_ SG_ 1088 Schaltung_aktiv__Getriebe_1_ "Shift Activity"; CM_ SG_ 1056 Fehlerstatus_Aussentemp__4_1 "ambient temp error"; CM_ SG_ 1056 Fehlerstatus_Oeltemperatur_4_1 "oil temp error"; diff --git a/panda/SConscript b/panda/SConscript index 34fddc49e5..357daba954 100644 --- a/panda/SConscript +++ b/panda/SConscript @@ -7,7 +7,7 @@ BUILDER = "DEV" common_flags = [] -panda_root = Dir('.').abspath +panda_root = Dir('.') if os.getenv("RELEASE"): BUILD_TYPE = "RELEASE" @@ -16,7 +16,7 @@ if os.getenv("RELEASE"): assert os.path.exists(cert_fn), 'Certificate file not found. Please specify absolute path' else: BUILD_TYPE = "DEBUG" - cert_fn = File("./certs/debug").srcnode().abspath + cert_fn = File("./certs/debug").srcnode().relpath common_flags += ["-DALLOW_DEBUG"] if os.getenv("DEBUG"): @@ -35,7 +35,7 @@ def get_version(builder, build_type): def get_key_header(name): from Crypto.PublicKey import RSA - public_fn = File(f'./certs/{name}.pub').srcnode().abspath + public_fn = File(f'./certs/{name}.pub').srcnode().get_path() with open(public_fn) as f: rsa = RSA.importKey(f.read()) assert(rsa.size_in_bits() == 1024) @@ -63,7 +63,7 @@ def to_c_uint32(x): def build_project(project_name, project, extra_flags): - linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().abspath + linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().relpath flags = project["PROJECT_FLAGS"] + extra_flags + common_flags + [ "-Wall", @@ -75,7 +75,7 @@ def build_project(project_name, project, extra_flags): "-nostdlib", "-fno-builtin", "-std=gnu11", - "-fmax-errors=3", + "-fmax-errors=1", f"-T{linkerscript_fn}", ] @@ -101,7 +101,8 @@ def build_project(project_name, project, extra_flags): ASCOM="$AS $ASFLAGS -o $TARGET -c $SOURCES", BUILDERS={ 'Objcopy': Builder(generator=objcopy, suffix='.bin', src_suffix='.elf') - } + }, + tools=["default", "compilation_db"], ) startup = env.Object(f"obj/startup_{project_name}", project["STARTUP_FILE"]) @@ -123,7 +124,7 @@ def build_project(project_name, project, extra_flags): main_bin = env.Objcopy(f"obj/{project_name}.bin", main_elf) # Sign main - sign_py = File(f"{panda_root}/crypto/sign.py").srcnode().abspath + sign_py = File(f"{panda_root}/crypto/sign.py").srcnode().relpath env.Command(f"obj/{project_name}.bin.signed", main_bin, f"SETLEN=1 {sign_py} $SOURCE $TARGET {cert_fn}") @@ -179,9 +180,6 @@ with open("board/obj/cert.h", "w") as f: # panda fw SConscript('board/SConscript') -# pedal fw -SConscript('board/pedal/SConscript') - # panda jungle fw SConscript('board/jungle/SConscript') diff --git a/panda/board/README.md b/panda/board/README.md index a6831e3a97..ab3d59d3e8 100644 --- a/panda/board/README.md +++ b/panda/board/README.md @@ -1,13 +1,14 @@ -Programming ----- - -**Panda** +## Programming ``` ./flash.py # flash application ./recover.py # flash bootstub ``` +## Debugging + +To print out the serial console from the STM32, run `tests/debug_console.py` + Troubleshooting ---- @@ -16,5 +17,4 @@ If panda is blinking fast with green LED, use `flash.py`. Otherwise if LED is off and panda can't be seen with `lsusb` command, use [panda paw](https://comma.ai/shop/products/panda-paw) to go into DFU mode. - If your device has an internal panda and none of the above works, try running `../tests/reflash_internal_panda.py`. diff --git a/panda/board/SConscript b/panda/board/SConscript index 45fa0f416e..93fd47b07e 100644 --- a/panda/board/SConscript +++ b/panda/board/SConscript @@ -12,7 +12,10 @@ for project_name, project in build_projects.items(): flags = [ "-DPANDA", ] - if ("ENABLE_SPI" in os.environ or "h7" in project_name) and not project_name.startswith('pedal'): + if ("ENABLE_SPI" in os.environ or "h7" in project_name): flags.append('-DENABLE_SPI') + if "H723" in os.environ: + flags.append('-DSTM32H723') + build_project(project_name, project, flags) diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h index caeffc3174..ea636334d2 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -1,6 +1,6 @@ -// ///////////////////// // -// Black Panda + Harness // -// ///////////////////// // +// /////////////////////////////// // +// Black Panda (STM32F4) + Harness // +// /////////////////////////////// // void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ @@ -136,7 +136,7 @@ void black_init(void) { // Set normal CAN mode black_set_can_mode(CAN_MODE_NORMAL); - // flip CAN0 and CAN2 if we are flipped + // change CAN mapping when flipped if (harness.status == HARNESS_STATUS_FLIPPED) { can_flip_buses(0, 2); } @@ -163,12 +163,9 @@ const harness_configuration black_harness_config = { }; const board board_black = { - .board_type = "Black", .set_bootkick = unused_set_bootkick, .harness_config = &black_harness_config, - .has_hw_gmlan = false, .has_obd = true, - .has_lin = false, .has_spi = false, .has_canfd = false, .has_rtc_battery = false, @@ -183,10 +180,10 @@ const board board_black = { .set_led = black_set_led, .set_can_mode = black_set_can_mode, .check_ignition = black_check_ignition, - .read_current = unused_read_current, + .read_voltage_mV = white_read_voltage_mV, + .read_current_mA = unused_read_current, .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, - .set_phone_power = unused_set_phone_power, .set_siren = unused_set_siren, .read_som_gpio = unused_read_som_gpio }; diff --git a/panda/board/boards/board_declarations.h b/panda/board/boards/board_declarations.h index fbf23783e0..600dc2884e 100644 --- a/panda/board/boards/board_declarations.h +++ b/panda/board/boards/board_declarations.h @@ -12,20 +12,17 @@ typedef void (*board_enable_can_transceivers)(bool enabled); typedef void (*board_set_led)(uint8_t color, bool enabled); typedef void (*board_set_can_mode)(uint8_t mode); typedef bool (*board_check_ignition)(void); -typedef uint32_t (*board_read_current)(void); +typedef uint32_t (*board_read_voltage_mV)(void); +typedef uint32_t (*board_read_current_mA)(void); typedef void (*board_set_ir_power)(uint8_t percentage); typedef void (*board_set_fan_enabled)(bool enabled); -typedef void (*board_set_phone_power)(bool enabled); typedef void (*board_set_siren)(bool enabled); typedef void (*board_set_bootkick)(BootState state); typedef bool (*board_read_som_gpio)(void); struct board { - const char *board_type; const harness_configuration *harness_config; - const bool has_hw_gmlan; const bool has_obd; - const bool has_lin; const bool has_spi; const bool has_canfd; const bool has_rtc_battery; @@ -40,10 +37,10 @@ struct board { board_set_led set_led; board_set_can_mode set_can_mode; board_check_ignition check_ignition; - board_read_current read_current; + board_read_voltage_mV read_voltage_mV; + board_read_current_mA read_current_mA; board_set_ir_power set_ir_power; board_set_fan_enabled set_fan_enabled; - board_set_phone_power set_phone_power; board_set_siren set_siren; board_set_bootkick set_bootkick; board_read_som_gpio read_som_gpio; @@ -61,6 +58,7 @@ struct board { #define HW_TYPE_RED_PANDA 7U #define HW_TYPE_RED_PANDA_V2 8U #define HW_TYPE_TRES 9U +#define HW_TYPE_CUATRO 10U // LED colors #define LED_RED 0U diff --git a/panda/board/boards/cuatro.h b/panda/board/boards/cuatro.h new file mode 100644 index 0000000000..b8cd3d035a --- /dev/null +++ b/panda/board/boards/cuatro.h @@ -0,0 +1,130 @@ +// ////////////////////////// // +// Cuatro (STM32H7) + Harness // +// ////////////////////////// // + +void cuatro_set_led(uint8_t color, bool enabled) { + switch (color) { + case LED_RED: + set_gpio_output(GPIOD, 15, !enabled); + break; + case LED_GREEN: + set_gpio_output(GPIOD, 14, !enabled); + break; + case LED_BLUE: + set_gpio_output(GPIOE, 2, !enabled); + break; + default: + break; + } +} + +void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver) { + case 1U: + set_gpio_output(GPIOB, 7, !enabled); + break; + case 2U: + set_gpio_output(GPIOB, 10, !enabled); + break; + case 3U: + set_gpio_output(GPIOD, 8, !enabled); + break; + case 4U: + set_gpio_output(GPIOB, 11, !enabled); + break; + default: + break; + } +} + +void cuatro_enable_can_transceivers(bool enabled) { + uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U; + for (uint8_t i=1U; i<=4U; i++) { + // Leave main CAN always on for CAN-based ignition detection + if (i == main_bus) { + cuatro_enable_can_transceiver(i, true); + } else { + cuatro_enable_can_transceiver(i, enabled); + } + } +} + +uint32_t cuatro_read_voltage_mV(void) { + return adc_get_mV(8) * 11U; +} + +uint32_t cuatro_read_current_mA(void) { + return adc_get_mV(3) * 2U; +} + +void cuatro_init(void) { + red_chiplet_init(); + + // Power readout + set_gpio_mode(GPIOC, 5, MODE_ANALOG); + set_gpio_mode(GPIOA, 6, MODE_ANALOG); + + // CAN transceiver enables + set_gpio_pullup(GPIOB, 7, PULL_NONE); + set_gpio_mode(GPIOB, 7, MODE_OUTPUT); + set_gpio_pullup(GPIOD, 8, PULL_NONE); + set_gpio_mode(GPIOD, 8, MODE_OUTPUT); + + // FDCAN3, different pins on this package than the rest of the reds + set_gpio_pullup(GPIOD, 12, PULL_NONE); + set_gpio_alternate(GPIOD, 12, GPIO_AF5_FDCAN3); + set_gpio_pullup(GPIOD, 13, PULL_NONE); + set_gpio_alternate(GPIOD, 13, GPIO_AF5_FDCAN3); + + // C2: SOM GPIO used as input (fan control at boot) + set_gpio_mode(GPIOC, 2, MODE_INPUT); + set_gpio_pullup(GPIOC, 2, PULL_DOWN); + + // SOM bootkick + reset lines + set_gpio_mode(GPIOC, 12, MODE_OUTPUT); + tres_set_bootkick(BOOT_BOOTKICK); + + // SOM debugging UART + gpio_uart7_init(); + uart_init(&uart_ring_som_debug, 115200); + + // SPI init + gpio_spi_init(); + + // fan setup + set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); + + // Initialize IR PWM and set to 0% + set_gpio_alternate(GPIOC, 9, GPIO_AF2_TIM3); + pwm_init(TIM3, 4); + tres_set_ir_power(0U); + + // Clock source + clock_source_init(); +} + +const board board_cuatro = { + .harness_config = &red_chiplet_harness_config, + .has_obd = true, + .has_spi = true, + .has_canfd = true, + .has_rtc_battery = true, + .fan_max_rpm = 6600U, + .avdd_mV = 1800U, + .fan_stall_recovery = false, + .fan_enable_cooldown_time = 3U, + .init = cuatro_init, + .init_bootloader = unused_init_bootloader, + .enable_can_transceiver = cuatro_enable_can_transceiver, + .enable_can_transceivers = cuatro_enable_can_transceivers, + .set_led = cuatro_set_led, + .set_can_mode = red_chiplet_set_can_mode, + .check_ignition = red_check_ignition, + .read_voltage_mV = cuatro_read_voltage_mV, + .read_current_mA = cuatro_read_current_mA, + .set_fan_enabled = tres_set_fan_enabled, + .set_ir_power = tres_set_ir_power, + .set_siren = unused_set_siren, + .set_bootkick = tres_set_bootkick, + .read_som_gpio = tres_read_som_gpio +}; diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index bdbf1723eb..428bbf2a5e 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -1,6 +1,6 @@ -// ///////////// // -// Dos + Harness // -// ///////////// // +// /////////////////////// // +// Dos (STM32F4) + Harness // +// /////////////////////// // void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ @@ -90,10 +90,6 @@ bool dos_check_ignition(void){ return harness_check_ignition(); } -void dos_set_usb_switch(bool phone){ - set_gpio_output(GPIOB, 3, phone); -} - void dos_set_ir_power(uint8_t percentage){ pwm_set(TIM4, 2, percentage); } @@ -168,7 +164,7 @@ void dos_init(void) { // Set normal CAN mode dos_set_can_mode(CAN_MODE_NORMAL); - // flip CAN0 and CAN2 if we are flipped + // change CAN mapping when flipped if (harness.status == HARNESS_STATUS_FLIPPED) { can_flip_buses(0, 2); } @@ -192,11 +188,8 @@ const harness_configuration dos_harness_config = { }; const board board_dos = { - .board_type = "Dos", .harness_config = &dos_harness_config, - .has_hw_gmlan = false, .has_obd = true, - .has_lin = false, #ifdef ENABLE_SPI .has_spi = true, #else @@ -215,10 +208,10 @@ const board board_dos = { .set_led = dos_set_led, .set_can_mode = dos_set_can_mode, .check_ignition = dos_check_ignition, - .read_current = unused_read_current, + .read_voltage_mV = white_read_voltage_mV, + .read_current_mA = unused_read_current, .set_fan_enabled = dos_set_fan_enabled, .set_ir_power = dos_set_ir_power, - .set_phone_power = unused_set_phone_power, .set_siren = dos_set_siren, .set_bootkick = dos_set_bootkick, .read_som_gpio = dos_read_som_gpio diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index 1aa2fdc3d7..8b3bd8aed5 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -1,16 +1,13 @@ -// ////////// // -// Grey Panda // -// ////////// // +// //////////////////// // +// Grey Panda (STM32F4) // +// //////////////////// // // Most hardware functionality is similar to white panda const board board_grey = { - .board_type = "Grey", .set_bootkick = unused_set_bootkick, .harness_config = &white_harness_config, - .has_hw_gmlan = true, .has_obd = false, - .has_lin = true, .has_spi = false, .has_canfd = false, .has_rtc_battery = false, @@ -25,10 +22,10 @@ const board board_grey = { .set_led = white_set_led, .set_can_mode = white_set_can_mode, .check_ignition = white_check_ignition, - .read_current = white_read_current, + .read_voltage_mV = white_read_voltage_mV, + .read_current_mA = white_read_current_mA, .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, - .set_phone_power = unused_set_phone_power, .set_siren = unused_set_siren, .read_som_gpio = unused_read_som_gpio }; diff --git a/panda/board/boards/pedal.h b/panda/board/boards/pedal.h deleted file mode 100644 index 42dd8f7efe..0000000000 --- a/panda/board/boards/pedal.h +++ /dev/null @@ -1,96 +0,0 @@ -// ///// // -// Pedal // -// ///// // - -void pedal_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver){ - case 1: - set_gpio_output(GPIOB, 3, !enabled); - break; - default: - print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n"); - break; - } -} - -void pedal_enable_can_transceivers(bool enabled) { - pedal_enable_can_transceiver(1U, enabled); -} - -void pedal_set_led(uint8_t color, bool enabled) { - switch (color){ - case LED_RED: - set_gpio_output(GPIOB, 10, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOB, 11, !enabled); - break; - default: - break; - } -} - -void pedal_set_can_mode(uint8_t mode){ - switch (mode) { - case CAN_MODE_NORMAL: - break; - default: - print("Tried to set unsupported CAN mode: "); puth(mode); print("\n"); - break; - } -} - -bool pedal_check_ignition(void){ - // not supported on pedal - return false; -} - -void pedal_init(void) { - common_init_gpio(); - - // C0, C1: Throttle inputs - set_gpio_mode(GPIOC, 0, MODE_ANALOG); - set_gpio_mode(GPIOC, 1, MODE_ANALOG); - // DAC outputs on A4 and A5 - // apparently they don't need GPIO setup - - // Enable transceiver - pedal_enable_can_transceivers(true); - - // Disable LEDs - pedal_set_led(LED_RED, false); - pedal_set_led(LED_GREEN, false); -} - -const harness_configuration pedal_harness_config = { - .has_harness = false -}; - -const board board_pedal = { - .board_type = "Pedal", - .set_bootkick = unused_set_bootkick, - .harness_config = &pedal_harness_config, - .has_hw_gmlan = false, - .has_obd = false, - .has_lin = false, - .has_spi = false, - .has_canfd = false, - .has_rtc_battery = false, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = pedal_init, - .init_bootloader = unused_init_bootloader, - .enable_can_transceiver = pedal_enable_can_transceiver, - .enable_can_transceivers = pedal_enable_can_transceivers, - .set_led = pedal_set_led, - .set_can_mode = pedal_set_can_mode, - .check_ignition = pedal_check_ignition, - .read_current = unused_read_current, - .set_fan_enabled = unused_set_fan_enabled, - .set_ir_power = unused_set_ir_power, - .set_phone_power = unused_set_phone_power, - .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/boards/red.h b/panda/board/boards/red.h index 16f68161a7..aa8c91be79 100644 --- a/panda/board/boards/red.h +++ b/panda/board/boards/red.h @@ -1,6 +1,6 @@ -// ///////////////////// // -// Red Panda + Harness // -// ///////////////////// // +// ///////////////////////////// // +// Red Panda (STM32H7) + Harness // +// ///////////////////////////// // void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver) { @@ -96,6 +96,10 @@ bool red_check_ignition(void) { return harness_check_ignition(); } +uint32_t red_read_voltage_mV(void){ + return adc_get_mV(2) * 11U; // TODO: is this correct? +} + void red_init(void) { common_init_gpio(); @@ -150,7 +154,7 @@ void red_init(void) { // Set normal CAN mode red_set_can_mode(CAN_MODE_NORMAL); - // flip CAN0 and CAN2 if we are flipped + // change CAN mapping when flipped if (harness.status == HARNESS_STATUS_FLIPPED) { can_flip_buses(0, 2); } @@ -171,12 +175,9 @@ const harness_configuration red_harness_config = { }; const board board_red = { - .board_type = "Red", .set_bootkick = unused_set_bootkick, .harness_config = &red_harness_config, - .has_hw_gmlan = false, .has_obd = true, - .has_lin = false, .has_spi = false, .has_canfd = true, .has_rtc_battery = false, @@ -191,10 +192,10 @@ const board board_red = { .set_led = red_set_led, .set_can_mode = red_set_can_mode, .check_ignition = red_check_ignition, - .read_current = unused_read_current, + .read_voltage_mV = red_read_voltage_mV, + .read_current_mA = unused_read_current, .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, - .set_phone_power = unused_set_phone_power, .set_siren = unused_set_siren, .read_som_gpio = unused_read_som_gpio }; diff --git a/panda/board/boards/red_chiplet.h b/panda/board/boards/red_chiplet.h index 1301cd3e54..eec3d95cdf 100644 --- a/panda/board/boards/red_chiplet.h +++ b/panda/board/boards/red_chiplet.h @@ -1,6 +1,6 @@ -// ///////////////////// // -// Red Panda chiplet + Harness // -// ///////////////////// // +// ///////////////////////////////////// // +// Red Panda chiplet (STM32H7) + Harness // +// ///////////////////////////////////// // // Most hardware functionality is similar to red panda @@ -133,7 +133,7 @@ void red_chiplet_init(void) { // Set normal CAN mode red_chiplet_set_can_mode(CAN_MODE_NORMAL); - // flip CAN0 and CAN2 if we are flipped + // change CAN mapping when flipped if (harness.status == HARNESS_STATUS_FLIPPED) { can_flip_buses(0, 2); } diff --git a/panda/board/boards/red_v2.h b/panda/board/boards/red_v2.h deleted file mode 100644 index 6554ef4e1e..0000000000 --- a/panda/board/boards/red_v2.h +++ /dev/null @@ -1,40 +0,0 @@ -// ///////////////////// // -// Red Panda V2 with chiplet + Harness // -// ///////////////////// // - -void red_panda_v2_init(void) { - // common chiplet init - red_chiplet_init(); - - // Turn on USB load switch - red_chiplet_set_fan_or_usb_load_switch(true); -} - -const board board_red_v2 = { - .board_type = "Red_v2", - .set_bootkick = unused_set_bootkick, - .harness_config = &red_chiplet_harness_config, - .has_hw_gmlan = false, - .has_obd = true, - .has_lin = false, - .has_spi = false, - .has_canfd = true, - .has_rtc_battery = true, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = red_panda_v2_init, - .init_bootloader = unused_init_bootloader, - .enable_can_transceiver = red_chiplet_enable_can_transceiver, - .enable_can_transceivers = red_chiplet_enable_can_transceivers, - .set_led = red_set_led, - .set_can_mode = red_chiplet_set_can_mode, - .check_ignition = red_check_ignition, - .read_current = unused_read_current, - .set_fan_enabled = unused_set_fan_enabled, - .set_ir_power = unused_set_ir_power, - .set_phone_power = unused_set_phone_power, - .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/boards/tres.h b/panda/board/boards/tres.h index da1cc7e68b..959c93b5d2 100644 --- a/panda/board/boards/tres.h +++ b/panda/board/boards/tres.h @@ -1,6 +1,6 @@ -// ///////////////// -// Tres + Harness // -// ///////////////// +// /////////////////////////// +// Tres (STM32H7) + Harness // +// /////////////////////////// bool tres_ir_enabled; bool tres_fan_enabled; @@ -71,11 +71,8 @@ void tres_init(void) { } const board board_tres = { - .board_type = "Tres", .harness_config = &red_chiplet_harness_config, - .has_hw_gmlan = false, .has_obd = true, - .has_lin = false, .has_spi = true, .has_canfd = true, .has_rtc_battery = true, @@ -90,10 +87,10 @@ const board board_tres = { .set_led = red_set_led, .set_can_mode = red_chiplet_set_can_mode, .check_ignition = red_check_ignition, - .read_current = unused_read_current, + .read_voltage_mV = red_read_voltage_mV, + .read_current_mA = unused_read_current, .set_fan_enabled = tres_set_fan_enabled, .set_ir_power = tres_set_ir_power, - .set_phone_power = unused_set_phone_power, .set_siren = fake_siren_set, .set_bootkick = tres_set_bootkick, .read_som_gpio = tres_read_som_gpio diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index 6fe6177399..f4e2016bd1 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -1,6 +1,6 @@ -// ///////////// // -// Uno + Harness // -// ///////////// // +// /////////////////////// // +// Uno (STM32F4) + Harness // +// /////////////////////// // void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ @@ -58,10 +58,6 @@ void uno_set_bootkick(BootState state) { } } -void uno_set_phone_power(bool enabled){ - set_gpio_output(GPIOB, 4, enabled); -} - void uno_set_can_mode(uint8_t mode) { uno_enable_can_transceiver(2U, false); uno_enable_can_transceiver(4U, false); @@ -141,7 +137,7 @@ void uno_init(void) { set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); // Turn on phone regulator - uno_set_phone_power(true); + set_gpio_output(GPIOB, 4, true); // Initialize IR PWM and set to 0% set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4); @@ -165,13 +161,13 @@ void uno_init(void) { // Set normal CAN mode uno_set_can_mode(CAN_MODE_NORMAL); - // flip CAN0 and CAN2 if we are flipped + // change CAN mapping when flipped if (harness.status == HARNESS_STATUS_FLIPPED) { can_flip_buses(0, 2); } // Switch to phone usb mode if harness connection is powered by less than 7V - if((adc_get_mV(ADCCHAN_VIN) * VIN_READOUT_DIVIDER) < 7000U){ + if(white_read_voltage_mV() < 7000U){ uno_set_usb_switch(true); } else { uno_set_usb_switch(false); @@ -203,11 +199,8 @@ const harness_configuration uno_harness_config = { }; const board board_uno = { - .board_type = "Uno", .harness_config = &uno_harness_config, - .has_hw_gmlan = false, .has_obd = true, - .has_lin = false, .has_spi = false, .has_canfd = false, .has_rtc_battery = true, @@ -222,10 +215,10 @@ const board board_uno = { .set_led = uno_set_led, .set_can_mode = uno_set_can_mode, .check_ignition = uno_check_ignition, - .read_current = unused_read_current, + .read_voltage_mV = white_read_voltage_mV, + .read_current_mA = unused_read_current, .set_fan_enabled = uno_set_fan_enabled, .set_ir_power = uno_set_ir_power, - .set_phone_power = uno_set_phone_power, .set_siren = unused_set_siren, .set_bootkick = uno_set_bootkick, .read_som_gpio = unused_read_som_gpio diff --git a/panda/board/boards/unused_funcs.h b/panda/board/boards/unused_funcs.h index edc83e3e05..7bfde01391 100644 --- a/panda/board/boards/unused_funcs.h +++ b/panda/board/boards/unused_funcs.h @@ -9,10 +9,6 @@ void unused_set_fan_enabled(bool enabled) { UNUSED(enabled); } -void unused_set_phone_power(bool enabled) { - UNUSED(enabled); -} - void unused_set_siren(bool enabled) { UNUSED(enabled); } diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index 4bd4381a51..0de29a39be 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -1,6 +1,6 @@ -// /////////// // -// White Panda // -// /////////// // +// ///////////////////// // +// White Panda (STM32F4) // +// ///////////////////// // void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ @@ -124,8 +124,13 @@ void white_set_can_mode(uint8_t mode){ } } -uint32_t white_read_current(void){ - return adc_get_raw(ADCCHAN_CURRENT); +uint32_t white_read_voltage_mV(void){ + return adc_get_mV(12) * 11U; +} + +uint32_t white_read_current_mA(void){ + // This isn't in mA, but we're keeping it for backwards compatibility + return adc_get_raw(13); } bool white_check_ignition(void){ @@ -197,10 +202,9 @@ void white_grey_init(void) { white_set_can_mode(CAN_MODE_NORMAL); // Init usb power mode - uint32_t voltage = adc_get_mV(ADCCHAN_VIN) * VIN_READOUT_DIVIDER; // Init in CDP mode only if panda is powered by 12V. // Otherwise a PC would not be able to flash a standalone panda - if (voltage > 8000U) { // 8V threshold + if (white_read_voltage_mV() > 8000U) { // 8V threshold white_set_usb_power_mode(USB_POWER_CDP); } else { white_set_usb_power_mode(USB_POWER_CLIENT); @@ -222,12 +226,9 @@ const harness_configuration white_harness_config = { }; const board board_white = { - .board_type = "White", .set_bootkick = unused_set_bootkick, .harness_config = &white_harness_config, - .has_hw_gmlan = true, .has_obd = false, - .has_lin = true, .has_spi = false, .has_canfd = false, .has_rtc_battery = false, @@ -242,10 +243,10 @@ const board board_white = { .set_led = white_set_led, .set_can_mode = white_set_can_mode, .check_ignition = white_check_ignition, - .read_current = white_read_current, + .read_voltage_mV = white_read_voltage_mV, + .read_current_mA = white_read_current_mA, .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, - .set_phone_power = unused_set_phone_power, .set_siren = unused_set_siren, .read_som_gpio = unused_read_som_gpio }; diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c index e2977e938c..aee665e7e0 100644 --- a/panda/board/bootstub.c +++ b/panda/board/bootstub.c @@ -19,6 +19,7 @@ #include "obj/gitversion.h" #include "flasher.h" +// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck void __initialize_hardware_early(void) { early_initialization(); } diff --git a/panda/board/can_comms.h b/panda/board/can_comms.h index 980d12ba8d..56ca912f8e 100644 --- a/panda/board/can_comms.h +++ b/panda/board/can_comms.h @@ -56,7 +56,7 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { asm_buffer can_write_buffer = {.ptr = 0U, .tail_size = 0U}; // send on CAN -void comms_can_write(uint8_t *data, uint32_t len) { +void comms_can_write(const uint8_t *data, uint32_t len) { uint32_t pos = 0U; // Assembling can message with data from buffer diff --git a/panda/board/can_definitions.h b/panda/board/can_definitions.h index daae4d0443..b3631d8071 100644 --- a/panda/board/can_definitions.h +++ b/panda/board/can_definitions.h @@ -8,7 +8,7 @@ const uint8_t PANDA_BUS_CNT = 4U; #define CANPACKET_HEAD_SIZE 6U -#if !defined(STM32F4) && !defined(STM32F2) +#if !defined(STM32F4) #define CANFD #define CANPACKET_DATA_SIZE_MAX 64U #else diff --git a/panda/board/comms_definitions.h b/panda/board/comms_definitions.h index d074514de4..18a6d2f813 100644 --- a/panda/board/comms_definitions.h +++ b/panda/board/comms_definitions.h @@ -6,7 +6,7 @@ typedef struct { } __attribute__((packed)) ControlPacket_t; int comms_control_handler(ControlPacket_t *req, uint8_t *resp); -void comms_endpoint2_write(uint8_t *data, uint32_t len); -void comms_can_write(uint8_t *data, uint32_t len); +void comms_endpoint2_write(const uint8_t *data, uint32_t len); +void comms_can_write(const uint8_t *data, uint32_t len); int comms_can_read(uint8_t *data, uint32_t max_len); void comms_can_reset(void); diff --git a/panda/board/config.h b/panda/board/config.h index 507d19e7d3..0adcc3e09a 100644 --- a/panda/board/config.h +++ b/panda/board/config.h @@ -16,8 +16,6 @@ #define MAX_CAN_MSGS_PER_USB_BULK_TRANSFER 51U #define MAX_CAN_MSGS_PER_SPI_BULK_TRANSFER 170U -#define VIN_READOUT_DIVIDER 11U - // USB definitions #define USB_VID 0xBBAAU @@ -38,7 +36,7 @@ // platform includes #ifdef STM32H7 #include "stm32h7/stm32h7_config.h" -#elif defined(STM32F2) || defined(STM32F4) +#elif defined(STM32F4) #include "stm32fx/stm32fx_config.h" #else // TODO: uncomment this, cppcheck complains diff --git a/panda/board/crc.h b/panda/board/crc.h index 6ceaba07ef..3e20fb0981 100644 --- a/panda/board/crc.h +++ b/panda/board/crc.h @@ -1,6 +1,6 @@ #pragma once -uint8_t crc_checksum(uint8_t *dat, int len, const uint8_t poly) { +uint8_t crc_checksum(const uint8_t *dat, int len, const uint8_t poly) { uint8_t crc = 0xFFU; int i; int j; diff --git a/panda/board/drivers/bxcan.h b/panda/board/drivers/bxcan.h index 080c9f4a9d..ea2705d9d0 100644 --- a/panda/board/drivers/bxcan.h +++ b/panda/board/drivers/bxcan.h @@ -23,56 +23,6 @@ bool can_set_speed(uint8_t can_number) { return ret; } -// TODO: Cleanup with new abstraction -void can_set_gmlan(uint8_t bus) { - if(current_board->has_hw_gmlan){ - // first, disable GMLAN on prev bus - uint8_t prev_bus = bus_config[3].can_num_lookup; - if (bus != prev_bus) { - switch (prev_bus) { - case 1: - case 2: - print("Disable GMLAN on CAN"); - puth(prev_bus + 1U); - print("\n"); - current_board->set_can_mode(CAN_MODE_NORMAL); - bus_config[prev_bus].bus_lookup = prev_bus; - bus_config[prev_bus].can_num_lookup = prev_bus; - bus_config[3].can_num_lookup = -1; - bool ret = can_init(prev_bus); - UNUSED(ret); - break; - default: - // GMLAN was not set on either BUS 1 or 2 - break; - } - } - - // now enable GMLAN on the new bus - switch (bus) { - case 1: - case 2: - print("Enable GMLAN on CAN"); - puth(bus + 1U); - print("\n"); - current_board->set_can_mode((bus == 1U) ? CAN_MODE_GMLAN_CAN2 : CAN_MODE_GMLAN_CAN3); - bus_config[bus].bus_lookup = 3; - bus_config[bus].can_num_lookup = -1; - bus_config[3].can_num_lookup = bus; - bool ret = can_init(bus); - UNUSED(ret); - break; - case 0xFF: //-1 unsigned - break; - default: - print("GMLAN can only be set on CAN2 or CAN3\n"); - break; - } - } else { - print("GMLAN not available on black panda\n"); - } -} - void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); uint32_t esr_reg = CANx->ESR; diff --git a/panda/board/drivers/can_common.h b/panda/board/drivers/can_common.h index 5c53862877..bc9adde7ce 100644 --- a/panda/board/drivers/can_common.h +++ b/panda/board/drivers/can_common.h @@ -28,8 +28,8 @@ extern int can_live; extern int pending_can_live; // must reinit after changing these -extern int can_loopback; extern int can_silent; +extern bool can_loopback; // Ignition detected from CAN meessages bool ignition_can = false; @@ -40,8 +40,8 @@ uint32_t ignition_can_cnt = 0U; int can_live = 0; int pending_can_live = 0; -int can_loopback = 0; int can_silent = ALL_CAN_SILENT; +bool can_loopback = false; // ******************* functions prototypes ********************* bool can_init(uint8_t can_number); @@ -95,7 +95,7 @@ bool can_pop(can_ring *q, CANPacket_t *elem) { return ret; } -bool can_push(can_ring *q, CANPacket_t *elem) { +bool can_push(can_ring *q, const CANPacket_t *elem) { bool ret = false; uint32_t next_w_ptr; @@ -133,7 +133,7 @@ bool can_push(can_ring *q, CANPacket_t *elem) { return ret; } -uint32_t can_slots_empty(can_ring *q) { +uint32_t can_slots_empty(const can_ring *q) { uint32_t ret = 0; ENTER_CRITICAL(); @@ -238,7 +238,7 @@ bool can_tx_check_min_slots_free(uint32_t min) { (can_slots_empty(&can_txgmlan_q) >= min); } -uint8_t calculate_checksum(uint8_t *dat, uint32_t len) { +uint8_t calculate_checksum(const uint8_t *dat, uint32_t len) { uint8_t checksum = 0U; for (uint32_t i = 0U; i < len; i++) { checksum ^= dat[i]; @@ -277,10 +277,10 @@ void can_send(CANPacket_t *to_push, uint8_t bus_number, bool skip_tx_hook) { } } -bool is_speed_valid(uint32_t speed, const uint32_t *speeds, uint8_t len) { +bool is_speed_valid(uint32_t speed, const uint32_t *all_speeds, uint8_t len) { bool ret = false; for (uint8_t i = 0U; i < len; i++) { - if (speeds[i] == speed) { + if (all_speeds[i] == speed) { ret = true; } } diff --git a/panda/board/drivers/fdcan.h b/panda/board/drivers/fdcan.h index 5104f3fec9..bc4c2a532e 100644 --- a/panda/board/drivers/fdcan.h +++ b/panda/board/drivers/fdcan.h @@ -35,11 +35,6 @@ bool can_set_speed(uint8_t can_number) { return ret; } -void can_set_gmlan(uint8_t bus) { - UNUSED(bus); - print("GMLAN not available on red panda\n"); -} - void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); uint32_t psr_reg = FDCANx->PSR; @@ -106,13 +101,15 @@ void process_can(uint8_t can_number) { uint32_t TxFIFOSA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET) + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE); // get the index of the next TX FIFO element (0 to FDCAN_TX_FIFO_EL_CNT - 1) - uint8_t tx_index = (FDCANx->TXFQS >> FDCAN_TXFQS_TFQPI_Pos) & 0x1F; + uint32_t tx_index = (FDCANx->TXFQS >> FDCAN_TXFQS_TFQPI_Pos) & 0x1F; // only send if we have received a packet canfd_fifo *fifo; fifo = (canfd_fifo *)(TxFIFOSA + (tx_index * FDCAN_TX_FIFO_EL_SIZE)); fifo->header[0] = (to_send.extended << 30) | ((to_send.extended != 0U) ? (to_send.addr) : (to_send.addr << 18)); - fifo->header[1] = (to_send.data_len_code << 16) | (bus_config[can_number].canfd_enabled << 21) | (bus_config[can_number].brs_enabled << 20); + uint32_t canfd_enabled_header = bus_config[can_number].canfd_enabled ? (1UL << 21) : 0UL; + uint32_t brs_enabled_header = bus_config[can_number].brs_enabled ? (1UL << 20) : 0UL; + fifo->header[1] = (to_send.data_len_code << 16) | canfd_enabled_header | brs_enabled_header; uint8_t data_len_w = (dlc_to_len[to_send.data_len_code] / 4U); data_len_w += ((dlc_to_len[to_send.data_len_code] % 4U) > 0U) ? 1U : 0U; @@ -163,7 +160,7 @@ void can_rx(uint8_t can_number) { pending_can_live = 1; // get the index of the next RX FIFO element (0 to FDCAN_RX_FIFO_0_EL_CNT - 1) - uint8_t rx_fifo_idx = (uint8_t)((FDCANx->RXF0S >> FDCAN_RXF0S_F0GI_Pos) & 0x3F); + uint32_t rx_fifo_idx = (uint8_t)((FDCANx->RXF0S >> FDCAN_RXF0S_F0GI_Pos) & 0x3F); // Recommended to offset get index by at least +1 if RX FIFO is in overwrite mode and full (datasheet) if((FDCANx->RXF0S & FDCAN_RXF0S_F0F) == FDCAN_RXF0S_F0F) { diff --git a/panda/board/drivers/gmlan_alt.h b/panda/board/drivers/gmlan_alt.h index 1c20e1ed79..2dbc381bd2 100644 --- a/panda/board/drivers/gmlan_alt.h +++ b/panda/board/drivers/gmlan_alt.h @@ -12,7 +12,7 @@ int gmlan_alt_mode = DISABLED; // returns out_len -int do_bitstuff(char *out, char *in, int in_len) { +int do_bitstuff(char *out, const char *in, int in_len) { int last_bit = -1; int bit_cnt = 0; int j = 0; @@ -22,18 +22,18 @@ int do_bitstuff(char *out, char *in, int in_len) { j++; // do the stuffing - if (bit == last_bit) { + if (bit == (char)last_bit) { bit_cnt++; if (bit_cnt == 5) { // 5 in a row the same, do stuff - last_bit = !bit; + last_bit = !bit ? 1 : 0; out[j] = last_bit; j++; bit_cnt = 1; } } else { // this is a new bit - last_bit = bit; + last_bit = (int)bit; bit_cnt = 1; } } @@ -57,7 +57,7 @@ int append_crc(char *in, int in_len) { return in_len_copy; } -int append_bits(char *in, int in_len, char *app, int app_len) { +int append_bits(char *in, int in_len, const char *app, int app_len) { int in_len_copy = in_len; for (int i = 0; i < app_len; i++) { in[in_len_copy] = app[i]; @@ -75,7 +75,7 @@ int append_int(char *in, int in_len, int val, int val_len) { return in_len_copy; } -int get_bit_message(char *out, CANPacket_t *to_bang) { +int get_bit_message(char *out, const CANPacket_t *to_bang) { char pkt[MAX_BITS_CAN_PACKET]; char footer[] = { 1, // CRC delimiter @@ -95,7 +95,7 @@ int get_bit_message(char *out, CANPacket_t *to_bang) { // extended identifier len = append_int(pkt, len, GET_ADDR(to_bang) >> 18, 11); // Identifier len = append_int(pkt, len, 3, 2); // SRR+IDE - len = append_int(pkt, len, (GET_ADDR(to_bang)) & ((1U << 18) - 1U), 18); // Identifier + len = append_int(pkt, len, (GET_ADDR(to_bang)) & ((1UL << 18) - 1U), 18); // Identifier len = append_int(pkt, len, 0, 3); // RTR+r1+r0 } else { // standard identifier @@ -121,23 +121,23 @@ int get_bit_message(char *out, CANPacket_t *to_bang) { return len; } -void GMLAN_BITBANG_IRQ_Handler(void); +void TIM12_IRQ_Handler(void); void setup_timer(void) { // register interrupt - REGISTER_INTERRUPT(GMLAN_BITBANG_TIMER_IRQ, GMLAN_BITBANG_IRQ_Handler, 40000U, FAULT_INTERRUPT_RATE_GMLAN) + REGISTER_INTERRUPT(TIM8_BRK_TIM12_IRQn, TIM12_IRQ_Handler, 40000U, FAULT_INTERRUPT_RATE_GMLAN) // setup - register_set(&(GMLAN_BITBANG_TIMER->PSC), (APB1_TIMER_FREQ-1U), 0xFFFFU); // Tick on 1 us - register_set(&(GMLAN_BITBANG_TIMER->CR1), TIM_CR1_CEN, 0x3FU); // Enable - register_set(&(GMLAN_BITBANG_TIMER->ARR), (30U-1U), 0xFFFFU); // 33.3 kbps + register_set(&(TIM12->PSC), (APB1_TIMER_FREQ-1U), 0xFFFFU); // Tick on 1 us + register_set(&(TIM12->CR1), TIM_CR1_CEN, 0x3FU); // Enable + register_set(&(TIM12->ARR), (30U-1U), 0xFFFFU); // 33.3 kbps // in case it's disabled - NVIC_EnableIRQ(GMLAN_BITBANG_TIMER_IRQ); + NVIC_EnableIRQ(TIM8_BRK_TIM12_IRQn); // run the interrupt - register_set(&(GMLAN_BITBANG_TIMER->DIER), TIM_DIER_UIE, 0x5F5FU); // Update interrupt - GMLAN_BITBANG_TIMER->SR = 0; + register_set(&(TIM12->DIER), TIM_DIER_UIE, 0x5F5FU); // Update interrupt + TIM12->SR = 0; } int gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; //GMLAN transceiver times out every 17ms held high; tickle every 15ms @@ -147,37 +147,11 @@ int inverted_bit_to_send = GMLAN_HIGH; int gmlan_switch_below_timeout = -1; int gmlan_switch_timeout_enable = 0; -void gmlan_switch_init(int timeout_enable) { - gmlan_switch_timeout_enable = timeout_enable; - gmlan_alt_mode = GPIO_SWITCH; - gmlan_switch_below_timeout = 1; - set_gpio_mode(GPIOB, 13, MODE_OUTPUT); - - setup_timer(); - - inverted_bit_to_send = GMLAN_LOW; //We got initialized, set the output low -} - -void set_gmlan_digital_output(int to_set) { - inverted_bit_to_send = to_set; - /* - print("Writing "); - puth(inverted_bit_to_send); - print("\n"); - */ -} - -void reset_gmlan_switch_timeout(void) { - can_timeout_counter = GMLAN_TICKS_PER_SECOND; - gmlan_switch_below_timeout = 1; - gmlan_alt_mode = GPIO_SWITCH; -} - void set_bitbanged_gmlan(int val) { if (val != 0) { - register_set_bits(&(GPIOB->ODR), (1U << 13)); + register_set_bits(&(GPIOB->ODR), (1UL << 13)); } else { - register_clear_bits(&(GPIOB->ODR), (1U << 13)); + register_clear_bits(&(GPIOB->ODR), (1UL << 13)); } } @@ -191,9 +165,9 @@ int gmlan_fail_count = 0; #define REQUIRED_SILENT_TIME 10 #define MAX_FAIL_COUNT 10 -void GMLAN_BITBANG_IRQ_Handler(void) { +void TIM12_IRQ_Handler(void) { if (gmlan_alt_mode == BITBANG) { - if ((GMLAN_BITBANG_TIMER->SR & TIM_SR_UIF) && (gmlan_sendmax != -1)) { + if ((TIM12->SR & TIM_SR_UIF) && (gmlan_sendmax != -1)) { int read = get_gpio_input(GPIOB, 12); if (gmlan_silent_count < REQUIRED_SILENT_TIME) { if (read == 0) { @@ -205,7 +179,7 @@ void GMLAN_BITBANG_IRQ_Handler(void) { bool retry = 0; // in send loop if ((gmlan_sending > 0) && // not first bit - ((read == 0) && (pkt_stuffed[gmlan_sending-1] == 1)) && // bus wrongly dominant + ((read == 0) && (pkt_stuffed[gmlan_sending-1] == (char)1)) && // bus wrongly dominant (gmlan_sending != (gmlan_sendmax - 11))) { //not ack bit print("GMLAN ERR: bus driven at "); puth(gmlan_sending); @@ -235,13 +209,13 @@ void GMLAN_BITBANG_IRQ_Handler(void) { if ((gmlan_sending == gmlan_sendmax) || (gmlan_fail_count == MAX_FAIL_COUNT)) { set_bitbanged_gmlan(1); // recessive set_gpio_mode(GPIOB, 13, MODE_INPUT); - register_clear_bits(&(GMLAN_BITBANG_TIMER->DIER), TIM_DIER_UIE); // No update interrupt - register_set(&(GMLAN_BITBANG_TIMER->CR1), 0U, 0x3FU); // Disable timer + register_clear_bits(&(TIM12->DIER), TIM_DIER_UIE); // No update interrupt + register_set(&(TIM12->CR1), 0U, 0x3FU); // Disable timer gmlan_sendmax = -1; // exit } } } else if (gmlan_alt_mode == GPIO_SWITCH) { - if ((GMLAN_BITBANG_TIMER->SR & TIM_SR_UIF) && (gmlan_switch_below_timeout != -1)) { + if ((TIM12->SR & TIM_SR_UIF) && (gmlan_switch_below_timeout != -1)) { if ((can_timeout_counter == 0) && gmlan_switch_timeout_enable) { //it has been more than 1 second since timeout was reset; disable timer and restore the GMLAN output set_gpio_output(GPIOB, 13, GMLAN_LOW); @@ -265,25 +239,32 @@ void GMLAN_BITBANG_IRQ_Handler(void) { } else { // Invalid GMLAN mode. Do not put a print statement here, way too fast to keep up with } - GMLAN_BITBANG_TIMER->SR = 0; + TIM12->SR = 0; } -bool bitbang_gmlan(CANPacket_t *to_bang) { +bool bitbang_gmlan(const CANPacket_t *to_bang) { gmlan_send_ok = true; gmlan_alt_mode = BITBANG; - if (gmlan_sendmax == -1) { - int len = get_bit_message(pkt_stuffed, to_bang); - gmlan_fail_count = 0; - gmlan_silent_count = 0; - gmlan_sending = 0; - gmlan_sendmax = len; - // setup for bitbang loop - set_bitbanged_gmlan(1); // recessive - set_gpio_mode(GPIOB, 13, MODE_OUTPUT); - - // 33kbps - setup_timer(); +#ifdef HW_TYPE_DOS + if (hw_type == HW_TYPE_DOS) { + if (gmlan_sendmax == -1) { + int len = get_bit_message(pkt_stuffed, to_bang); + gmlan_fail_count = 0; + gmlan_silent_count = 0; + gmlan_sending = 0; + gmlan_sendmax = len; + // setup for bitbang loop + set_bitbanged_gmlan(1); // recessive + set_gpio_mode(GPIOB, 13, MODE_OUTPUT); + + // 33kbps + setup_timer(); + } } +#else + UNUSED(to_bang); +#endif + return gmlan_send_ok; } diff --git a/panda/board/drivers/gpio.h b/panda/board/drivers/gpio.h index fe3194f3ba..bf96a0326e 100644 --- a/panda/board/drivers/gpio.h +++ b/panda/board/drivers/gpio.h @@ -27,9 +27,9 @@ void set_gpio_mode(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) { ENTER_CRITICAL(); if (enabled) { - register_set_bits(&(GPIO->ODR), (1U << pin)); + register_set_bits(&(GPIO->ODR), (1UL << pin)); } else { - register_clear_bits(&(GPIO->ODR), (1U << pin)); + register_clear_bits(&(GPIO->ODR), (1UL << pin)); } set_gpio_mode(GPIO, pin, MODE_OUTPUT); EXIT_CRITICAL(); @@ -38,7 +38,7 @@ void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) { void set_gpio_output_type(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int output_type){ ENTER_CRITICAL(); if(output_type == OUTPUT_TYPE_OPEN_DRAIN) { - register_set_bits(&(GPIO->OTYPER), (1U << pin)); + register_set_bits(&(GPIO->OTYPER), (1UL << pin)); } else { register_clear_bits(&(GPIO->OTYPER), (1U << pin)); } @@ -64,8 +64,8 @@ void set_gpio_pullup(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { EXIT_CRITICAL(); } -int get_gpio_input(GPIO_TypeDef *GPIO, unsigned int pin) { - return (GPIO->IDR & (1U << pin)) == (1U << pin); +int get_gpio_input(const GPIO_TypeDef *GPIO, unsigned int pin) { + return (GPIO->IDR & (1UL << pin)) == (1UL << pin); } void gpio_set_all_output(const gpio_t *pins, uint8_t num_pins, bool enabled) { diff --git a/panda/board/drivers/harness.h b/panda/board/drivers/harness.h index 36f73f2573..60f99fc85c 100644 --- a/panda/board/drivers/harness.h +++ b/panda/board/drivers/harness.h @@ -39,7 +39,7 @@ void set_intercept_relay(bool intercept, bool ignition_relay) { } // wait until we're not reading the analog voltages anymore - while (harness.sbu_adc_lock == true) {} + while (harness.sbu_adc_lock) {} if (harness.status == HARNESS_STATUS_NORMAL) { set_gpio_output(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, !ignition_relay); @@ -59,7 +59,7 @@ bool harness_check_ignition(void) { bool ret = false; // wait until we're not reading the analog voltages anymore - while (harness.sbu_adc_lock == true) {} + while (harness.sbu_adc_lock) {} switch(harness.status){ case HARNESS_STATUS_NORMAL: @@ -95,6 +95,7 @@ uint8_t harness_detect_orientation(void) { ret = HARNESS_STATUS_FLIPPED; } else { // orientation normal (PANDA_SBU2->HARNESS_SBU1(relay), PANDA_SBU1->HARNESS_SBU2(ign)) + // (SBU1->SBU2 is the normal orientation connection per USB-C cable spec) ret = HARNESS_STATUS_NORMAL; } } else { diff --git a/panda/board/drivers/interrupts.h b/panda/board/drivers/interrupts.h index 9cb46d4b29..d4c72be1df 100644 --- a/panda/board/drivers/interrupts.h +++ b/panda/board/drivers/interrupts.h @@ -78,8 +78,8 @@ void interrupt_timer_handler(void) { // Calculate interrupt load // The bootstub does not have the FPU enabled, so can't do float operations. -#if !defined(PEDAL) && !defined(BOOTSTUB) - interrupt_load = ((busy_time + idle_time) > 0U) ? ((float) busy_time) / (busy_time + idle_time) : 0.0f; +#if !defined(BOOTSTUB) + interrupt_load = ((busy_time + idle_time) > 0U) ? ((float) (((float) busy_time) / (busy_time + idle_time))) : 0.0f; #endif idle_time = 0U; busy_time = 0U; diff --git a/panda/board/drivers/kline_init.h b/panda/board/drivers/kline_init.h deleted file mode 100644 index a8a859cba7..0000000000 --- a/panda/board/drivers/kline_init.h +++ /dev/null @@ -1,119 +0,0 @@ -void TIM5_IRQ_Handler(void); - -void setup_timer5(void) { - // register interrupt - REGISTER_INTERRUPT(TIM5_IRQn, TIM5_IRQ_Handler, 1050000U, FAULT_INTERRUPT_RATE_KLINE_INIT) - - // setup - register_set(&(TIM5->PSC), (48-1), 0xFFFFU); // Tick on 1 us - register_set(&(TIM5->CR1), TIM_CR1_CEN, 0x3FU); // Enable - register_set(&(TIM5->ARR), (5000-1), 0xFFFFFFFFU); // Reset every 5 ms - - // in case it's disabled - NVIC_EnableIRQ(TIM5_IRQn); - - // run the interrupt - register_set(&(TIM5->DIER), TIM_DIER_UIE, 0x5F5FU); // Update interrupt - TIM5->SR = 0; -} - -bool k_init = false; -bool l_init = false; -void setup_kline(bool bitbang) { - if (bitbang) { - if (k_init) { - set_gpio_output(GPIOC, 12, true); - } - if (l_init) { - set_gpio_output(GPIOC, 10, true); - } - } else { - if (k_init) { - set_gpio_mode(GPIOC, 12, MODE_ALTERNATE); - } - if (l_init) { - set_gpio_mode(GPIOC, 10, MODE_ALTERNATE); - } - } -} - -void set_bitbanged_kline(bool marking) { - // tickle needs to be super fast (so logic level doesn't change) - ENTER_CRITICAL(); - if (k_init) { - register_set_bits(&(GPIOC->ODR), (1U << 12)); - if (!marking) { - register_clear_bits(&(GPIOC->ODR), (1U << 12)); - } - } - if (l_init) { - register_set_bits(&(GPIOC->ODR), (1U << 10)); - if (!marking) { - register_clear_bits(&(GPIOC->ODR), (1U << 10)); - } - } - EXIT_CRITICAL(); - // blink blue LED each time line is pulled low - current_board->set_led(LED_BLUE, marking); -} - -uint16_t kline_data = 0; -uint16_t kline_data_len = 0; -uint16_t kline_bit_count = 0; -uint16_t kline_tick_count = 0; -uint16_t kline_ticks_per_bit = 0; - -void TIM5_IRQ_Handler(void) { - if ((TIM5->SR & TIM_SR_UIF) && (kline_data != 0U)) { - if (kline_bit_count < kline_data_len) { - bool marking = (kline_data & (1U << kline_bit_count)) != 0U; - set_bitbanged_kline(marking); - } else { - register_clear_bits(&(TIM5->DIER), TIM_DIER_UIE); // No update interrupt - register_set(&(TIM5->CR1), 0U, 0x3FU); // Disable timer - setup_kline(false); - kline_data = 0U; - USB_WritePacket(NULL, 0, 0); // required call (so send nothing) - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - } - kline_tick_count++; - if ((kline_tick_count % kline_ticks_per_bit) == 0U) { - kline_bit_count++; - } - } - TIM5->SR = 0; -} - -bool bitbang_five_baud_addr(bool k, bool l, uint8_t addr) { - bool result = false; - if (kline_data == 0U) { - k_init = k; - l_init = l; - kline_data = (addr << 1) + 0x200U; // add start/stop bits - kline_data_len = 10U; - kline_bit_count = 0; - kline_tick_count = 0; - kline_ticks_per_bit = 40U; // 200ms == 5bps - setup_kline(true); - setup_timer5(); - result = true; - } - return result; -} - -bool bitbang_wakeup(bool k, bool l) { - bool result = false; - if (kline_data == 0U) { - k_init = k; - l_init = l; - kline_data = 2U; // low then high - kline_data_len = 2U; - kline_bit_count = 0; - kline_tick_count = 0; - kline_ticks_per_bit = 5U; // 25ms == 40bps - setup_kline(true); - setup_timer5(); - result = true; - } - return result; -} diff --git a/panda/board/drivers/spi.h b/panda/board/drivers/spi.h index 6d0beda9ad..1a7b9be590 100644 --- a/panda/board/drivers/spi.h +++ b/panda/board/drivers/spi.h @@ -43,6 +43,8 @@ uint16_t spi_data_len_miso; uint16_t spi_checksum_error_count = 0; bool spi_can_tx_ready = false; +const char version_text[] = "VERSION"; + #define SPI_HEADER_SIZE 7U // low level SPI prototypes @@ -64,7 +66,7 @@ uint16_t spi_version_packet(uint8_t *out) { // VERSION + 2 byte data length + data + CRC8 // echo "VERSION" - (void)memcpy(out, "VERSION", 7); + (void)memcpy(out, version_text, 7); // write response uint16_t data_len = 0; @@ -109,7 +111,7 @@ void spi_init(void) { llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); } -bool check_checksum(uint8_t *data, uint16_t len) { +bool validate_checksum(const uint8_t *data, uint16_t len) { // TODO: can speed this up by casting the bulk to uint32_t and xor-ing the bytes afterwards uint8_t checksum = SPI_CHECKSUM_START; for(uint16_t i = 0U; i < len; i++){ @@ -128,11 +130,11 @@ void spi_rx_done(void) { spi_data_len_mosi = (spi_buf_rx[3] << 8) | spi_buf_rx[2]; spi_data_len_miso = (spi_buf_rx[5] << 8) | spi_buf_rx[4]; - if (memcmp(spi_buf_rx, "VERSION", 7) == 0) { + if (memcmp(spi_buf_rx, version_text, 7) == 0) { response_len = spi_version_packet(spi_buf_tx); next_rx_state = SPI_STATE_HEADER_NACK;; } else if (spi_state == SPI_STATE_HEADER) { - checksum_valid = check_checksum(spi_buf_rx, SPI_HEADER_SIZE); + checksum_valid = validate_checksum(spi_buf_rx, SPI_HEADER_SIZE); if ((spi_buf_rx[0] == SPI_SYNC_BYTE) && checksum_valid) { // response: ACK and start receiving data portion spi_buf_tx[0] = SPI_HACK; @@ -148,7 +150,7 @@ void spi_rx_done(void) { } else if (spi_state == SPI_STATE_DATA_RX) { // We got everything! Based on the endpoint specified, call the appropriate handler bool response_ack = false; - checksum_valid = check_checksum(&(spi_buf_rx[SPI_HEADER_SIZE]), spi_data_len_mosi + 1U); + checksum_valid = validate_checksum(&(spi_buf_rx[SPI_HEADER_SIZE]), spi_data_len_mosi + 1U); if (checksum_valid) { if (spi_endpoint == 0U) { if (spi_data_len_mosi >= sizeof(ControlPacket_t)) { diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index cde8137402..01d8c2ac05 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -41,11 +41,6 @@ void uart_send_break(uart_ring *u); // ******************************** UART buffers ******************************** -// lin1, K-LINE = UART5 -// lin2, L-LINE = USART3 -UART_BUFFER(lin1, FIFO_SIZE_INT, FIFO_SIZE_INT, UART5, NULL, false) -UART_BUFFER(lin2, FIFO_SIZE_INT, FIFO_SIZE_INT, USART3, NULL, false) - // debug = USART2 UART_BUFFER(debug, FIFO_SIZE_INT, FIFO_SIZE_INT, USART2, debug_ring_callback, true) @@ -63,12 +58,6 @@ uart_ring *get_ring_by_number(int a) { case 0: ring = &uart_ring_debug; break; - case 2: - ring = &uart_ring_lin1; - break; - case 3: - ring = &uart_ring_lin2; - break; case 4: ring = &uart_ring_som_debug; break; @@ -80,7 +69,7 @@ uart_ring *get_ring_by_number(int a) { } // ************************* Low-level buffer functions ************************* -bool getc(uart_ring *q, char *elem) { +bool get_char(uart_ring *q, char *elem) { bool ret = false; ENTER_CRITICAL(); @@ -116,7 +105,7 @@ bool injectc(uart_ring *q, char elem) { return ret; } -bool putc(uart_ring *q, char elem) { +bool put_char(uart_ring *q, char elem) { bool ret = false; uint16_t next_w_ptr; @@ -140,21 +129,6 @@ bool putc(uart_ring *q, char elem) { return ret; } -// Seems dangerous to use (might lock CPU if called with interrupts disabled f.e.) -// TODO: Remove? Not used anyways -void uart_flush(uart_ring *q) { - while (q->w_ptr_tx != q->r_ptr_tx) { - __WFI(); - } -} - -void uart_flush_sync(uart_ring *q) { - // empty the TX buffer - while (q->w_ptr_tx != q->r_ptr_tx) { - uart_tx_ring(q); - } -} - void clear_uart_buff(uart_ring *q) { ENTER_CRITICAL(); q->w_ptr_tx = 0; diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index c291d7e64c..1872dd5276 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -79,7 +79,7 @@ void refresh_can_tx_slots_available(void); #define STS_SETUP_COMP 4 #define STS_SETUP_UPDT 6 -uint8_t resp[USBPACKET_MAX_SIZE]; +uint8_t response[USBPACKET_MAX_SIZE]; // for the repeating interfaces #define DSCR_INTERFACE_LEN 9 @@ -104,7 +104,7 @@ uint8_t resp[USBPACKET_MAX_SIZE]; // Convert machine byte order to USB byte order #define TOUSBORDER(num)\ - ((num) & 0xFFU), (((num) >> 8) & 0xFFU) + ((num) & 0xFFU), (((uint16_t)(num) >> 8) & 0xFFU) // take in string length and return the first 2 bytes of a string descriptor #define STRING_DESCRIPTOR_HEADER(size)\ @@ -198,13 +198,8 @@ uint16_t string_product_desc[] = { // default serial number when we're not a panda uint16_t string_serial_desc[] = { -#ifdef PEDAL - STRING_DESCRIPTOR_HEADER(5), - 'p', 'e', 'd', 'a', 'l' -#else STRING_DESCRIPTOR_HEADER(4), 'n', 'o', 'n', 'e' -#endif }; // a string containing the default configuration index @@ -425,15 +420,15 @@ void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { void usb_reset(void) { // unmask endpoint interrupts, so many sets - USBx_DEVICE->DAINT = 0xFFFFFFFF; - USBx_DEVICE->DAINTMSK = 0xFFFFFFFF; + USBx_DEVICE->DAINT = 0xFFFFFFFFU; + USBx_DEVICE->DAINTMSK = 0xFFFFFFFFU; //USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM); //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK); //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM); // all interrupts for debugging - USBx_DEVICE->DIEPMSK = 0xFFFFFFFF; - USBx_DEVICE->DOEPMSK = 0xFFFFFFFF; + USBx_DEVICE->DIEPMSK = 0xFFFFFFFFU; + USBx_DEVICE->DOEPMSK = 0xFFFFFFFFU; // clear interrupts USBx_INEP(0)->DIEPINT = 0xFF; @@ -447,10 +442,10 @@ void usb_reset(void) { USBx->GRXFSIZ = 0x40; // 0x100 to offset past GRXFSIZ - USBx->DIEPTXF0_HNPTXFSIZ = (0x40U << 16) | 0x40U; + USBx->DIEPTXF0_HNPTXFSIZ = (0x40UL << 16) | 0x40U; // EP1, massive - USBx->DIEPTXF[0] = (0x40U << 16) | 0x80U; + USBx->DIEPTXF[0] = (0x40UL << 16) | 0x80U; // flush TX fifo USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4; @@ -463,15 +458,15 @@ void usb_reset(void) { USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; // ready to receive setup packets - USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)) | (3U << 3); + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (3U << 3); } -char to_hex_char(int a) { +char to_hex_char(uint8_t a) { char ret; - if (a < 10) { + if (a < 10U) { ret = '0' + a; } else { - ret = 'a' + (a - 10); + ret = 'a' + (a - 10U); } return ret; } @@ -490,17 +485,17 @@ void usb_setup(void) { switch (setup.b.bRequest) { case USB_REQ_SET_CONFIGURATION: // enable other endpoints, has to be here? - USBx_INEP(1)->DIEPCTL = (0x40U & USB_OTG_DIEPCTL_MPSIZ) | (2U << 18) | (1U << 22) | + USBx_INEP(1)->DIEPCTL = (0x40U & USB_OTG_DIEPCTL_MPSIZ) | (2UL << 18) | (1UL << 22) | USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP; USBx_INEP(1)->DIEPINT = 0xFF; - USBx_OUTEP(2)->DOEPTSIZ = (1U << 19) | 0x40U; - USBx_OUTEP(2)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2U << 18) | + USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U; + USBx_OUTEP(2)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2UL << 18) | USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; USBx_OUTEP(2)->DOEPINT = 0xFF; - USBx_OUTEP(3)->DOEPTSIZ = (32U << 19) | 0x800U; - USBx_OUTEP(3)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2U << 18) | + USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U; + USBx_OUTEP(3)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2UL << 18) | USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; USBx_OUTEP(3)->DOEPINT = 0xFF; @@ -557,19 +552,19 @@ void usb_setup(void) { break; case STRING_OFFSET_ISERIAL: #ifdef UID_BASE - resp[0] = 0x02 + (12 * 4); - resp[1] = 0x03; + response[0] = 0x02 + (12 * 4); + response[1] = 0x03; // 96 bits = 12 bytes for (int i = 0; i < 12; i++){ uint8_t cc = ((uint8_t *)UID_BASE)[i]; - resp[2 + (i * 4) + 0] = to_hex_char((cc >> 4) & 0xFU); - resp[2 + (i * 4) + 1] = '\0'; - resp[2 + (i * 4) + 2] = to_hex_char((cc >> 0) & 0xFU); - resp[2 + (i * 4) + 3] = '\0'; + response[2 + (i * 4)] = to_hex_char((cc >> 4) & 0xFU); + response[2 + (i * 4) + 1] = '\0'; + response[2 + (i * 4) + 2] = to_hex_char((cc >> 0) & 0xFU); + response[2 + (i * 4) + 3] = '\0'; } - USB_WritePacket(resp, MIN(resp[0], setup.b.wLength.w), 0); + USB_WritePacket(response, MIN(response[0], setup.b.wLength.w), 0); #else USB_WritePacket((const uint8_t *)string_serial_desc, MIN(sizeof(string_serial_desc), setup.b.wLength.w), 0); #endif @@ -599,10 +594,10 @@ void usb_setup(void) { } break; case USB_REQ_GET_STATUS: - // empty resp? - resp[0] = 0; - resp[1] = 0; - USB_WritePacket((void*)&resp, 2, 0); + // empty response? + response[0] = 0; + response[1] = 0; + USB_WritePacket((void*)&response, 2, 0); USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; break; case USB_REQ_SET_INTERFACE: @@ -648,10 +643,10 @@ void usb_setup(void) { control_req.param2 = setup.b.wIndex.w; control_req.length = setup.b.wLength.w; - resp_len = comms_control_handler(&control_req, resp); + resp_len = comms_control_handler(&control_req, response); // response pending if -1 was returned if (resp_len != -1) { - USB_WritePacket(resp, MIN(resp_len, setup.b.wLength.w), 0); + USB_WritePacket(response, MIN(resp_len, setup.b.wLength.w), 0); USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; } } @@ -802,7 +797,7 @@ void usb_irqhandler(void) { #ifdef DEBUG_USB print(" OUT2 PACKET XFRC\n"); #endif - USBx_OUTEP(2)->DOEPTSIZ = (1U << 19) | 0x40U; + USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U; USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; } @@ -833,7 +828,7 @@ void usb_irqhandler(void) { if ((USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) != 0) { // ready for next packet - USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)) | (1U << 3); + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (1U << 3); } // respond to setup packets @@ -877,7 +872,7 @@ void usb_irqhandler(void) { print(" IN PACKET QUEUE\n"); #endif // TODO: always assuming max len, can we get the length? - USB_WritePacket((void *)resp, comms_can_read(resp, 0x40), 1); + USB_WritePacket((void *)response, comms_can_read(response, 0x40), 1); } break; @@ -888,9 +883,9 @@ void usb_irqhandler(void) { print(" IN PACKET QUEUE\n"); #endif // TODO: always assuming max len, can we get the length? - int len = comms_can_read(resp, 0x40); + int len = comms_can_read(response, 0x40); if (len > 0) { - USB_WritePacket((void *)resp, len, 1); + USB_WritePacket((void *)response, len, 1); } } break; @@ -933,7 +928,7 @@ void usb_irqhandler(void) { void can_tx_comms_resume_usb(void) { ENTER_CRITICAL(); if (!outep3_processing && (USBx_OUTEP(3)->DOEPCTL & USB_OTG_DOEPCTL_NAKSTS) != 0) { - USBx_OUTEP(3)->DOEPTSIZ = (32U << 19) | 0x800U; + USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U; USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; } EXIT_CRITICAL(); diff --git a/panda/board/drivers/watchdog.h b/panda/board/drivers/watchdog.h index d0ee32cb2d..89cf01e07e 100644 --- a/panda/board/drivers/watchdog.h +++ b/panda/board/drivers/watchdog.h @@ -1,9 +1,3 @@ -// TODO: why doesn't it define these? -#ifdef STM32F2 -#define IWDG_PR_PR_Msk 0x7U -#define IWDG_RLR_RL_Msk 0xFFFU -#endif - typedef enum { WATCHDOG_50_MS = (400U - 1U), WATCHDOG_500_MS = 4000U, diff --git a/panda/board/faults.h b/panda/board/faults.h index 6c6bef475d..a7f437dee5 100644 --- a/panda/board/faults.h +++ b/panda/board/faults.h @@ -3,33 +3,33 @@ #define FAULT_STATUS_PERMANENT 2U // Fault types, matches cereal.log.PandaState.FaultType -#define FAULT_RELAY_MALFUNCTION (1U << 0) -#define FAULT_UNUSED_INTERRUPT_HANDLED (1U << 1) -#define FAULT_INTERRUPT_RATE_CAN_1 (1U << 2) -#define FAULT_INTERRUPT_RATE_CAN_2 (1U << 3) -#define FAULT_INTERRUPT_RATE_CAN_3 (1U << 4) -#define FAULT_INTERRUPT_RATE_TACH (1U << 5) -#define FAULT_INTERRUPT_RATE_GMLAN (1U << 6) -#define FAULT_INTERRUPT_RATE_INTERRUPTS (1U << 7) -#define FAULT_INTERRUPT_RATE_SPI_DMA (1U << 8) -#define FAULT_INTERRUPT_RATE_SPI_CS (1U << 9) -#define FAULT_INTERRUPT_RATE_UART_1 (1U << 10) -#define FAULT_INTERRUPT_RATE_UART_2 (1U << 11) -#define FAULT_INTERRUPT_RATE_UART_3 (1U << 12) -#define FAULT_INTERRUPT_RATE_UART_5 (1U << 13) -#define FAULT_INTERRUPT_RATE_UART_DMA (1U << 14) -#define FAULT_INTERRUPT_RATE_USB (1U << 15) -#define FAULT_INTERRUPT_RATE_TIM1 (1U << 16) -#define FAULT_INTERRUPT_RATE_TIM3 (1U << 17) -#define FAULT_REGISTER_DIVERGENT (1U << 18) -#define FAULT_INTERRUPT_RATE_KLINE_INIT (1U << 19) -#define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1U << 20) -#define FAULT_INTERRUPT_RATE_TICK (1U << 21) -#define FAULT_INTERRUPT_RATE_EXTI (1U << 22) -#define FAULT_INTERRUPT_RATE_SPI (1U << 23) -#define FAULT_INTERRUPT_RATE_UART_7 (1U << 24) -#define FAULT_SIREN_MALFUNCTION (1U << 25) -#define FAULT_HEARTBEAT_LOOP_WATCHDOG (1U << 26) +#define FAULT_RELAY_MALFUNCTION (1UL << 0) +#define FAULT_UNUSED_INTERRUPT_HANDLED (1UL << 1) +#define FAULT_INTERRUPT_RATE_CAN_1 (1UL << 2) +#define FAULT_INTERRUPT_RATE_CAN_2 (1UL << 3) +#define FAULT_INTERRUPT_RATE_CAN_3 (1UL << 4) +#define FAULT_INTERRUPT_RATE_TACH (1UL << 5) +#define FAULT_INTERRUPT_RATE_GMLAN (1UL << 6) +#define FAULT_INTERRUPT_RATE_INTERRUPTS (1UL << 7) +#define FAULT_INTERRUPT_RATE_SPI_DMA (1UL << 8) +#define FAULT_INTERRUPT_RATE_SPI_CS (1UL << 9) +#define FAULT_INTERRUPT_RATE_UART_1 (1UL << 10) +#define FAULT_INTERRUPT_RATE_UART_2 (1UL << 11) +#define FAULT_INTERRUPT_RATE_UART_3 (1UL << 12) +#define FAULT_INTERRUPT_RATE_UART_5 (1UL << 13) +#define FAULT_INTERRUPT_RATE_UART_DMA (1UL << 14) +#define FAULT_INTERRUPT_RATE_USB (1UL << 15) +#define FAULT_INTERRUPT_RATE_TIM1 (1UL << 16) +#define FAULT_INTERRUPT_RATE_TIM3 (1UL << 17) +#define FAULT_REGISTER_DIVERGENT (1UL << 18) +#define FAULT_INTERRUPT_RATE_KLINE_INIT (1UL << 19) +#define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1UL << 20) +#define FAULT_INTERRUPT_RATE_TICK (1UL << 21) +#define FAULT_INTERRUPT_RATE_EXTI (1UL << 22) +#define FAULT_INTERRUPT_RATE_SPI (1UL << 23) +#define FAULT_INTERRUPT_RATE_UART_7 (1UL << 24) +#define FAULT_SIREN_MALFUNCTION (1UL << 25) +#define FAULT_HEARTBEAT_LOOP_WATCHDOG (1UL << 26) // Permanent faults #define PERMANENT_FAULTS 0U diff --git a/panda/board/flasher.h b/panda/board/flasher.h index 495d9f1691..d6c2c40211 100644 --- a/panda/board/flasher.h +++ b/panda/board/flasher.h @@ -4,10 +4,6 @@ bool unlocked = false; void spi_init(void); -#ifdef uart_ring -void debug_ring_callback(uart_ring *ring) {} -#endif - int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { int resp_len = 0; @@ -50,23 +46,19 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { break; // **** 0xc3: fetch MCU UID case 0xc3: - #ifdef UID_BASE - (void)memcpy(resp, ((uint8_t *)UID_BASE), 12); - resp_len = 12; - #endif + (void)memcpy(resp, ((uint8_t *)UID_BASE), 12); + resp_len = 12; break; // **** 0xd0: fetch serial number case 0xd0: - #ifndef STM32F2 - // addresses are OTP - if (req->param1 == 1) { - memcpy(resp, (void *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); - resp_len = 0x10; - } else { - get_provision_chunk(resp); - resp_len = PROVISION_CHUNK_LEN; - } - #endif + // addresses are OTP + if (req->param1 == 1) { + memcpy(resp, (void *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); + resp_len = 0x10; + } else { + get_provision_chunk(resp); + resp_len = PROVISION_CHUNK_LEN; + } break; // **** 0xd1: enter bootloader mode case 0xd1: @@ -99,7 +91,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { return resp_len; } -void comms_can_write(uint8_t *data, uint32_t len) { +void comms_can_write(const uint8_t *data, uint32_t len) { UNUSED(data); UNUSED(len); } @@ -112,7 +104,7 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { void refresh_can_tx_slots_available(void) {} -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +void comms_endpoint2_write(const uint8_t *data, uint32_t len) { current_board->set_led(LED_RED, 0); for (uint32_t i = 0; i < len/4; i++) { flash_write_word(prog_ptr, *(uint32_t*)(data+(i*4))); @@ -124,172 +116,13 @@ void comms_endpoint2_write(uint8_t *data, uint32_t len) { } -int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { - UNUSED(len); - ControlPacket_t control_req; - - int resp_len = 0; - switch (data[0]) { - case 0: - // control transfer - control_req.request = ((USB_Setup_TypeDef *)(data+4))->b.bRequest; - control_req.param1 = ((USB_Setup_TypeDef *)(data+4))->b.wValue.w; - control_req.param2 = ((USB_Setup_TypeDef *)(data+4))->b.wIndex.w; - control_req.length = ((USB_Setup_TypeDef *)(data+4))->b.wLength.w; - - resp_len = comms_control_handler(&control_req, data_out); - break; - case 2: - // ep 2, flash! - comms_endpoint2_write(data+4, data[2]); - break; - } - return resp_len; -} - -#ifdef PEDAL - -#include "stm32fx/llbxcan.h" -#define CANx CAN1 - -#define CAN_BL_INPUT 0x1 -#define CAN_BL_OUTPUT 0x2 - -void CAN1_TX_IRQ_Handler(void) { - // clear interrupt - CANx->TSR |= CAN_TSR_RQCP0; -} - -#define ISOTP_BUF_SIZE 0x110 - -uint8_t isotp_buf[ISOTP_BUF_SIZE]; -uint8_t *isotp_buf_ptr = NULL; -int isotp_buf_remain = 0; - -uint8_t isotp_buf_out[ISOTP_BUF_SIZE]; -uint8_t *isotp_buf_out_ptr = NULL; -int isotp_buf_out_remain = 0; -int isotp_buf_out_idx = 0; - -void bl_can_send(uint8_t *odat) { - // wait for send - while (!(CANx->TSR & CAN_TSR_TME0)); - - // send continue - CANx->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0]; - CANx->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1]; - CANx->sTxMailBox[0].TDTR = 8; - CANx->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1; -} - -void CAN1_RX0_IRQ_Handler(void) { - while (CANx->RF0R & CAN_RF0R_FMP0) { - if ((CANx->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) { - uint8_t dat[8]; - for (int i = 0; i < 8; i++) { - dat[i] = GET_MAILBOX_BYTE(&CANx->sFIFOMailBox[0], i); - } - uint8_t odat[8]; - uint8_t type = dat[0] & 0xF0; - if (type == 0x30) { - // continue - while (isotp_buf_out_remain > 0) { - // wait for send - while (!(CANx->TSR & CAN_TSR_TME0)); - - odat[0] = 0x20 | isotp_buf_out_idx; - memcpy(odat+1, isotp_buf_out_ptr, 7); - isotp_buf_out_remain -= 7; - isotp_buf_out_ptr += 7; - isotp_buf_out_idx++; - - bl_can_send(odat); - } - } else if (type == 0x20) { - if (isotp_buf_remain > 0) { - memcpy(isotp_buf_ptr, dat+1, 7); - isotp_buf_ptr += 7; - isotp_buf_remain -= 7; - } - if (isotp_buf_remain <= 0) { - int len = isotp_buf_ptr - isotp_buf + isotp_buf_remain; - - // call the function - memset(isotp_buf_out, 0, ISOTP_BUF_SIZE); - isotp_buf_out_remain = spi_cb_rx(isotp_buf, len, isotp_buf_out); - isotp_buf_out_ptr = isotp_buf_out; - isotp_buf_out_idx = 0; - - // send initial - if (isotp_buf_out_remain <= 7) { - odat[0] = isotp_buf_out_remain; - memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain); - } else { - odat[0] = 0x10 | (isotp_buf_out_remain>>8); - odat[1] = isotp_buf_out_remain & 0xFF; - memcpy(odat+2, isotp_buf_out_ptr, 6); - isotp_buf_out_remain -= 6; - isotp_buf_out_ptr += 6; - isotp_buf_out_idx++; - } - - bl_can_send(odat); - } - } else if (type == 0x10) { - int len = ((dat[0]&0xF)<<8) | dat[1]; - - // setup buffer - isotp_buf_ptr = isotp_buf; - memcpy(isotp_buf_ptr, dat+2, 6); - - if (len < (ISOTP_BUF_SIZE-0x10)) { - isotp_buf_ptr += 6; - isotp_buf_remain = len-6; - } - - memset(odat, 0, 8); - odat[0] = 0x30; - bl_can_send(odat); - } - } - // next - CANx->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN1_SCE_IRQ_Handler(void) { - llcan_clear_send(CANx); -} - -#endif - void soft_flasher_start(void) { - #ifdef PEDAL - REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - #endif - print("\n\n\n************************ FLASHER START ************************\n"); enter_bootloader_mode = 0; flasher_peripherals_init(); -// pedal has the canloader -#ifdef PEDAL - RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; - - // B8,B9: CAN 1 - set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); - set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); - current_board->enable_can_transceiver(1, true); - - // init can - llcan_set_speed(CANx, 5000, false, false); - llcan_init(CANx); -#endif - gpio_usart2_init(); gpio_usb_init(); diff --git a/panda/board/health.h b/panda/board/health.h index a1b7ed952f..fc7661ca9c 100644 --- a/panda/board/health.h +++ b/panda/board/health.h @@ -1,6 +1,6 @@ // When changing these structs, python/__init__.py needs to be kept up to date! -#define HEALTH_PACKET_VERSION 14 +#define HEALTH_PACKET_VERSION 15 struct __attribute__((packed)) health_t { uint32_t uptime_pkt; uint32_t voltage_pkt; @@ -14,7 +14,6 @@ struct __attribute__((packed)) health_t { uint8_t ignition_line_pkt; uint8_t ignition_can_pkt; uint8_t controls_allowed_pkt; - uint8_t gas_interceptor_detected_pkt; uint8_t car_harness_status_pkt; uint8_t safety_mode_pkt; uint16_t safety_param_pkt; @@ -22,10 +21,10 @@ struct __attribute__((packed)) health_t { uint8_t power_save_enabled_pkt; uint8_t heartbeat_lost_pkt; uint16_t alternative_experience_pkt; - float interrupt_load; + float interrupt_load_pkt; uint8_t fan_power; - uint8_t safety_rx_checks_invalid; - uint16_t spi_checksum_error_count; + uint8_t safety_rx_checks_invalid_pkt; + uint16_t spi_checksum_error_count_pkt; uint8_t fan_stall_count; uint16_t sbu1_voltage_mV; uint16_t sbu2_voltage_mV; diff --git a/panda/board/jungle/boards/board_declarations.h b/panda/board/jungle/boards/board_declarations.h index 6e016af071..925918921f 100644 --- a/panda/board/jungle/boards/board_declarations.h +++ b/panda/board/jungle/boards/board_declarations.h @@ -15,7 +15,6 @@ typedef float (*board_get_channel_power)(uint8_t channel); typedef uint16_t (*board_get_sbu_mV)(uint8_t channel, uint8_t sbu); struct board { - const char *board_type; const bool has_canfd; const bool has_sbu_sense; const uint16_t avdd_mV; @@ -36,7 +35,6 @@ struct board { // TODO: shouldn't need these bool has_spi; - bool has_hw_gmlan; }; // ******************* Definitions ******************** diff --git a/panda/board/jungle/boards/board_v1.h b/panda/board/jungle/boards/board_v1.h index d0ad7843eb..9581686e2a 100644 --- a/panda/board/jungle/boards/board_v1.h +++ b/panda/board/jungle/boards/board_v1.h @@ -1,3 +1,6 @@ +// ///////////////////////// // +// Jungle board v1 (STM32F4) // +// ///////////////////////// // void board_v1_set_led(uint8_t color, bool enabled) { switch (color) { @@ -155,7 +158,6 @@ void board_v1_init(void) { void board_v1_tick(void) {} const board board_v1 = { - .board_type = "V1", .has_canfd = false, .has_sbu_sense = false, .avdd_mV = 3300U, diff --git a/panda/board/jungle/boards/board_v2.h b/panda/board/jungle/boards/board_v2.h index 25ea2fd422..095114825b 100644 --- a/panda/board/jungle/boards/board_v2.h +++ b/panda/board/jungle/boards/board_v2.h @@ -1,3 +1,6 @@ +// ///////////////////////// // +// Jungle board v2 (STM32H7) // +// ///////////////////////// // const gpio_t power_pins[] = { {.bank = GPIOA, .pin = 0}, @@ -305,7 +308,6 @@ void board_v2_init(void) { void board_v2_tick(void) {} const board board_v2 = { - .board_type = "V2", .has_canfd = true, .has_sbu_sense = true, .avdd_mV = 3300U, diff --git a/panda/board/jungle/main.c b/panda/board/jungle/main.c index 3ab39ba1d6..f0a09dfbde 100644 --- a/panda/board/jungle/main.c +++ b/panda/board/jungle/main.c @@ -31,7 +31,7 @@ void debug_ring_callback(uart_ring *ring) { char rcv; - while (getc(ring, &rcv)) { + while (get_char(ring, &rcv)) { (void)injectc(ring, rcv); } } @@ -155,7 +155,7 @@ int main(void) { } print("Config:\n"); - print(" Board type: "); print(current_board->board_type); print("\n"); + print(" Board type: 0x"); puth(hw_type); print("\n"); // init board current_board->init(); diff --git a/panda/board/jungle/main_comms.h b/panda/board/jungle/main_comms.h index 49d16e5745..928c554d1c 100644 --- a/panda/board/jungle/main_comms.h +++ b/panda/board/jungle/main_comms.h @@ -29,7 +29,7 @@ int get_jungle_health_pkt(void *dat) { } // send on serial, first byte to select the ring -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +void comms_endpoint2_write(const uint8_t *data, uint32_t len) { UNUSED(data); UNUSED(len); } @@ -192,7 +192,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { // **** 0xe0: debug read case 0xe0: // read - while ((resp_len < MIN(req->length, USBPACKET_MAX_SIZE)) && getc(get_ring_by_number(0), (char*)&resp[resp_len])) { + while ((resp_len < MIN(req->length, USBPACKET_MAX_SIZE)) && get_char(get_ring_by_number(0), (char*)&resp[resp_len])) { ++resp_len; } break; diff --git a/panda/board/libc.h b/panda/board/libc.h index 1e32d4206e..7f669b95ab 100644 --- a/panda/board/libc.h +++ b/panda/board/libc.h @@ -5,6 +5,7 @@ void delay(uint32_t a) { for (i = 0; i < a; i++); } +// cppcheck-suppress misra-c2012-21.2 void *memset(void *str, int c, unsigned int n) { uint8_t *s = str; for (unsigned int i = 0; i < n; i++) { @@ -17,6 +18,7 @@ void *memset(void *str, int c, unsigned int n) { #define UNALIGNED(X, Y) \ (((uint32_t)(X) & (sizeof(uint32_t) - 1U)) | ((uint32_t)(Y) & (sizeof(uint32_t) - 1U))) +// cppcheck-suppress misra-c2012-21.2 void *memcpy(void *dest, const void *src, unsigned int len) { unsigned int n = len; uint8_t *d8 = dest; @@ -48,6 +50,7 @@ void *memcpy(void *dest, const void *src, unsigned int len) { return dest; } +// cppcheck-suppress misra-c2012-21.2 int memcmp(const void * ptr1, const void * ptr2, unsigned int num) { int ret = 0; const uint8_t *p1 = ptr1; diff --git a/panda/board/main.c b/panda/board/main.c index 0d692d0e91..061a913814 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -4,7 +4,6 @@ #include "drivers/pwm.h" #include "drivers/usb.h" #include "drivers/gmlan_alt.h" -#include "drivers/kline_init.h" #include "drivers/simple_watchdog.h" #include "drivers/bootkick.h" @@ -41,8 +40,8 @@ bool check_started(void) { void debug_ring_callback(uart_ring *ring) { char rcv; - while (getc(ring, &rcv)) { - (void)putc(ring, rcv); // misra-c2012-17.7: cast to void is ok: debug function + while (get_char(ring, &rcv)) { + (void)put_char(ring, rcv); // misra-c2012-17.7: cast to void is ok: debug function // only allow bootloader entry on debug builds #ifdef ALLOW_DEBUG @@ -272,7 +271,7 @@ void tick_handler(void) { ignition_can_cnt += 1U; // synchronous safety check - safety_tick(current_rx_checks); + safety_tick(¤t_safety_config); } loop_counter++; @@ -339,7 +338,7 @@ int main(void) { } print("Config:\n"); - print(" Board type: "); print(current_board->board_type); print("\n"); + print(" Board type: 0x"); puth(hw_type); print("\n"); // init board current_board->init(); @@ -347,14 +346,6 @@ int main(void) { // panda has an FPU, let's use it! enable_fpu(); - if (current_board->has_lin) { - // enable LIN - uart_init(&uart_ring_lin1, 10400); - UART5->CR2 |= USART_CR2_LINEN; - uart_init(&uart_ring_lin2, 10400); - USART3->CR2 |= USART_CR2_LINEN; - } - if (current_board->fan_max_rpm > 0U) { fan_init(); } @@ -393,9 +384,7 @@ int main(void) { enable_interrupts(); // LED should keep on blinking all the time - uint64_t cnt = 0; - - for (cnt=0;;cnt++) { + while (true) { if (power_save_status == POWER_SAVE_STATUS_DISABLED) { #ifdef DEBUG_FAULTS if (fault_status == FAULT_STATUS_NONE) { diff --git a/panda/board/main_comms.h b/panda/board/main_comms.h index c821f4cfc1..c0d5c516fb 100644 --- a/panda/board/main_comms.h +++ b/panda/board/main_comms.h @@ -9,15 +9,14 @@ int get_health_pkt(void *dat) { struct health_t * health = (struct health_t*)dat; health->uptime_pkt = uptime_cnt; - health->voltage_pkt = adc_get_mV(ADCCHAN_VIN) * VIN_READOUT_DIVIDER; - health->current_pkt = current_board->read_current(); + health->voltage_pkt = current_board->read_voltage_mV(); + health->current_pkt = current_board->read_current_mA(); // Use the GPIO pin to determine ignition or use a CAN based logic health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); - health->ignition_can_pkt = (uint8_t)(ignition_can); + health->ignition_can_pkt = ignition_can; health->controls_allowed_pkt = controls_allowed; - health->gas_interceptor_detected_pkt = gas_interceptor_detected; health->safety_tx_blocked_pkt = safety_tx_blocked; health->safety_rx_invalid_pkt = safety_rx_invalid; health->tx_buffer_overflow_pkt = tx_buffer_overflow; @@ -27,16 +26,16 @@ int get_health_pkt(void *dat) { health->safety_mode_pkt = (uint8_t)(current_safety_mode); health->safety_param_pkt = current_safety_param; health->alternative_experience_pkt = alternative_experience; - health->power_save_enabled_pkt = (uint8_t)(power_save_status == POWER_SAVE_STATUS_ENABLED); - health->heartbeat_lost_pkt = (uint8_t)(heartbeat_lost); - health->safety_rx_checks_invalid = safety_rx_checks_invalid; + health->power_save_enabled_pkt = power_save_status == POWER_SAVE_STATUS_ENABLED; + health->heartbeat_lost_pkt = heartbeat_lost; + health->safety_rx_checks_invalid_pkt = safety_rx_checks_invalid; - health->spi_checksum_error_count = spi_checksum_error_count; + health->spi_checksum_error_count_pkt = spi_checksum_error_count; health->fault_status_pkt = fault_status; health->faults_pkt = faults; - health->interrupt_load = interrupt_load; + health->interrupt_load_pkt = interrupt_load; health->fan_power = fan_state.power; health->fan_stall_count = fan_state.total_stall_count; @@ -56,12 +55,12 @@ int get_rtc_pkt(void *dat) { } // send on serial, first byte to select the ring -void comms_endpoint2_write(uint8_t *data, uint32_t len) { +void comms_endpoint2_write(const uint8_t *data, uint32_t len) { uart_ring *ur = get_ring_by_number(data[0]); if ((len != 0U) && (ur != NULL)) { - if ((data[0] < 2U) || (data[0] >= 4U) || safety_tx_lin_hook(data[0] - 2U, &data[1], len - 1U)) { + if ((data[0] < 2U) || (data[0] >= 4U)) { for (uint32_t i = 1; i < len; i++) { - while (!putc(ur, data[i])) { + while (!put_char(ur, data[i])) { // wait } } @@ -152,10 +151,6 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { resp[1] = ((fan_state.rpm & 0xFF00U) >> 8U); resp_len = 2; break; - // **** 0xb3: set phone power - case 0xb3: - current_board->set_phone_power(req->param1 > 0U); - break; // **** 0xc0: reset communications case 0xc0: comms_can_reset(); @@ -279,19 +274,6 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { // Disable OBD CAN current_board->set_can_mode(CAN_MODE_NORMAL); } - } else { - if (req->param1 == 1U) { - // GMLAN ON - if (req->param2 == 1U) { - can_set_gmlan(1); - } else if (req->param2 == 2U) { - can_set_gmlan(2); - } else { - print("Invalid bus num for GMLAN CAN set\n"); - } - } else { - can_set_gmlan(-1); - } } break; @@ -329,8 +311,9 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { } // read - while ((resp_len < MIN(req->length, USBPACKET_MAX_SIZE)) && - getc(ur, (char*)&resp[resp_len])) { + uint16_t req_length = MIN(req->length, USBPACKET_MAX_SIZE); + while ((resp_len < req_length) && + get_char(ur, (char*)&resp[resp_len])) { ++resp_len; } break; @@ -377,7 +360,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { break; // **** 0xe5: set CAN loopback (for testing) case 0xe5: - can_loopback = (req->param1 > 0U); + can_loopback = req->param1 > 0U; can_init_all(); break; // **** 0xe6: set custom clock source period @@ -388,16 +371,6 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { case 0xe7: set_power_save_state(req->param1); break; - // **** 0xf0: k-line/l-line wake-up pulse for KWP2000 fast initialization - case 0xf0: - if(current_board->has_lin) { - bool k = (req->param1 == 0U) || (req->param1 == 2U); - bool l = (req->param1 == 1U) || (req->param1 == 2U); - if (bitbang_wakeup(k, l)) { - resp_len = -1; // do not clear NAK yet (wait for bit banging to finish) - } - } - break; // **** 0xf1: Clear CAN ring buffer. case 0xf1: if (req->param1 == 0xFFFFU) { @@ -429,17 +402,6 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { heartbeat_engaged = (req->param1 == 1U); break; } - // **** 0xf4: k-line/l-line 5 baud initialization - case 0xf4: - if(current_board->has_lin) { - bool k = (req->param1 == 0U) || (req->param1 == 2U); - bool l = (req->param1 == 1U) || (req->param1 == 2U); - uint8_t five_baud_addr = (req->param2 & 0xFFU); - if (bitbang_five_baud_addr(k, l, five_baud_addr)) { - resp_len = -1; // do not clear NAK yet (wait for bit banging to finish) - } - } - break; // **** 0xf6: set siren enabled case 0xf6: siren_enabled = (req->param1 != 0U); diff --git a/panda/board/pedal/.gitignore b/panda/board/pedal/.gitignore deleted file mode 100644 index 94053f2925..0000000000 --- a/panda/board/pedal/.gitignore +++ /dev/null @@ -1 +0,0 @@ -obj/* diff --git a/panda/board/pedal/README.md b/panda/board/pedal/README.md deleted file mode 100644 index 9e004d6bd8..0000000000 --- a/panda/board/pedal/README.md +++ /dev/null @@ -1,28 +0,0 @@ -# pedal - -This is the firmware for the comma pedal. - -The comma pedal is a gas pedal interceptor for Honda/Acura and Toyota/Lexus. It allows you to "virtually" press the pedal and borrows a lot from panda. - -== Test Plan == - -* Startup -** Confirm STATE_FAULT_STARTUP -* Timeout -** Send value -** Confirm value is output -** Stop sending messages -** Confirm value is passthru after 100ms -** Confirm STATE_FAULT_TIMEOUT -* Random values -** Send random 6 byte messages -** Confirm random values cause passthru -** Confirm STATE_FAULT_BAD_CHECKSUM -* Same message lockout -** Send same message repeated -** Confirm timeout behavior -* Don't set enable -** Confirm no output -* Set enable and values -** Confirm output - diff --git a/panda/board/pedal/SConscript b/panda/board/pedal/SConscript deleted file mode 100644 index bfa3c2c19d..0000000000 --- a/panda/board/pedal/SConscript +++ /dev/null @@ -1,28 +0,0 @@ -import copy - -Import('build_project') - -build_projects = {} - -build_projects["pedal"] = { - "MAIN": "main.c", - "BOOTSTUB": "../bootstub.c", - "STARTUP_FILE": "../stm32fx/startup_stm32f205xx.s", - "LINKER_SCRIPT": "../stm32fx/stm32f2_flash.ld", - "APP_START_ADDRESS": "0x8004000", - "PROJECT_FLAGS": [ - "-mcpu=cortex-m3", - "-msoft-float", - "-DSTM32F2", - "-DSTM32F205xx", - "-O2", - "-DPEDAL", - ], -} - -# build with the USB driver enabled -build_projects["pedal_usb"] = copy.deepcopy(build_projects["pedal"]) -build_projects["pedal_usb"]["PROJECT_FLAGS"].append("-DPEDAL_USB") - -for project_name, project in build_projects.items(): - build_project(project_name, project, []) diff --git a/panda/board/pedal/flash_can.sh b/panda/board/pedal/flash_can.sh deleted file mode 100755 index b9edf25f12..0000000000 --- a/panda/board/pedal/flash_can.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env sh -set -e - -cd .. -scons -u -j$(nproc) -cd pedal - -../../tests/pedal/enter_canloader.py obj/pedal.bin.signed diff --git a/panda/board/pedal/main.c b/panda/board/pedal/main.c deleted file mode 100644 index e0020f1123..0000000000 --- a/panda/board/pedal/main.c +++ /dev/null @@ -1,316 +0,0 @@ -// ********************* Includes ********************* -//#define PEDAL_USB -#include "../config.h" - -#include "early_init.h" -#include "crc.h" - -#define CAN CAN1 - -#ifdef PEDAL_USB - #include "drivers/usb.h" -#else - // no serial either - void print(const char *a) { - UNUSED(a); - } - void puth(unsigned int i) { - UNUSED(i); - } - void puth2(unsigned int i) { - UNUSED(i); - } -#endif - -#define ENTER_BOOTLOADER_MAGIC 0xdeadbeefU -uint32_t enter_bootloader_mode; - -// cppcheck-suppress unusedFunction ; used in headers not included in cppcheck -void __initialize_hardware_early(void) { - early_initialization(); -} - -// ********************* serial debugging ********************* - -#ifdef PEDAL_USB - -void debug_ring_callback(uart_ring *ring) { - char rcv; - while (getc(ring, &rcv) != 0) { - (void)putc(ring, rcv); - } -} - -int comms_can_read(uint8_t *data, uint32_t max_len) { - UNUSED(data); - UNUSED(max_len); - return 0; -} -void comms_can_write(uint8_t *data, uint32_t len) { - UNUSED(data); - UNUSED(len); -} -void comms_endpoint2_write(uint8_t *data, uint32_t len) { - UNUSED(data); - UNUSED(len); -} -void refresh_can_tx_slots_available(void) {} - -int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { - unsigned int resp_len = 0; - uart_ring *ur = NULL; - switch (req->request) { - // **** 0xc1: get hardware type - case 0xc1: - resp[0] = hw_type; - resp_len = 1; - break; - // **** 0xe0: uart read - case 0xe0: - ur = get_ring_by_number(req->param1); - if (!ur) { - break; - } - // read - while ((resp_len < MIN(req->length, USBPACKET_MAX_SIZE)) && - getc(ur, (char*)&resp[resp_len])) { - ++resp_len; - } - break; - default: - print("NO HANDLER "); - puth(req->request); - print("\n"); - break; - } - return resp_len; -} - -#endif - -// ***************************** can port ***************************** - -// addresses to be used on CAN -#define CAN_GAS_INPUT 0x200 -#define CAN_GAS_OUTPUT 0x201U -#define CAN_GAS_SIZE 6 -#define COUNTER_CYCLE 0xFU - -void CAN1_TX_IRQ_Handler(void) { - // clear interrupt - CAN->TSR |= CAN_TSR_RQCP0; -} - -// two independent values -uint16_t gas_set_0 = 0; -uint16_t gas_set_1 = 0; - -#define MAX_TIMEOUT 10U -uint32_t timeout = 0; -uint32_t current_index = 0; - -#define NO_FAULT 0U -#define FAULT_BAD_CHECKSUM 1U -#define FAULT_SEND 2U -#define FAULT_SCE 3U -#define FAULT_STARTUP 4U -#define FAULT_TIMEOUT 5U -#define FAULT_INVALID 6U -uint8_t state = FAULT_STARTUP; -const uint8_t crc_poly = 0xD5U; // standard crc8 - -void CAN1_RX0_IRQ_Handler(void) { - while ((CAN->RF0R & CAN_RF0R_FMP0) != 0) { - #ifdef DEBUG - print("CAN RX\n"); - #endif - int address = CAN->sFIFOMailBox[0].RIR >> 21; - if (address == CAN_GAS_INPUT) { - // softloader entry - if (GET_MAILBOX_BYTES_04(&CAN->sFIFOMailBox[0]) == 0xdeadface) { - if (GET_MAILBOX_BYTES_48(&CAN->sFIFOMailBox[0]) == 0x0ab00b1e) { - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - } else if (GET_MAILBOX_BYTES_48(&CAN->sFIFOMailBox[0]) == 0x02b00b1e) { - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - NVIC_SystemReset(); - } else { - print("Failed entering Softloader or Bootloader\n"); - } - } - - // normal packet - uint8_t dat[8]; - for (int i=0; i<8; i++) { - dat[i] = GET_MAILBOX_BYTE(&CAN->sFIFOMailBox[0], i); - } - uint16_t value_0 = (dat[0] << 8) | dat[1]; - uint16_t value_1 = (dat[2] << 8) | dat[3]; - bool enable = ((dat[4] >> 7) & 1U) != 0U; - uint8_t index = dat[4] & COUNTER_CYCLE; - if (crc_checksum(dat, CAN_GAS_SIZE - 1, crc_poly) == dat[5]) { - if (((current_index + 1U) & COUNTER_CYCLE) == index) { - #ifdef DEBUG - print("setting gas "); - puth(value_0); - print("\n"); - #endif - if (enable) { - gas_set_0 = value_0; - gas_set_1 = value_1; - } else { - // clear the fault state if values are 0 - if ((value_0 == 0U) && (value_1 == 0U)) { - state = NO_FAULT; - } else { - state = FAULT_INVALID; - } - gas_set_0 = 0; - gas_set_1 = 0; - } - // clear the timeout - timeout = 0; - } - current_index = index; - } else { - // wrong checksum = fault - state = FAULT_BAD_CHECKSUM; - } - } - // next - CAN->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN1_SCE_IRQ_Handler(void) { - state = FAULT_SCE; - llcan_clear_send(CAN); -} - -uint32_t pdl0 = 0; -uint32_t pdl1 = 0; -unsigned int pkt_idx = 0; - -int led_value = 0; - -void TIM3_IRQ_Handler(void) { - #ifdef DEBUG - puth(TIM3->CNT); - print(" "); - puth(pdl0); - print(" "); - puth(pdl1); - print("\n"); - #endif - - // check timer for sending the user pedal and clearing the CAN - if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { - uint8_t dat[8]; - dat[0] = (pdl0 >> 8) & 0xFFU; - dat[1] = (pdl0 >> 0) & 0xFFU; - dat[2] = (pdl1 >> 8) & 0xFFU; - dat[3] = (pdl1 >> 0) & 0xFFU; - dat[4] = ((state & 0xFU) << 4) | pkt_idx; - dat[5] = crc_checksum(dat, CAN_GAS_SIZE - 1, crc_poly); - CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1] << 8) | (dat[2] << 16) | (dat[3] << 24); - CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5] << 8); - CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5 - CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1U; - ++pkt_idx; - pkt_idx &= COUNTER_CYCLE; - } else { - // old can packet hasn't sent! - state = FAULT_SEND; - #ifdef DEBUG - print("CAN MISS\n"); - #endif - } - - // blink the LED - current_board->set_led(LED_GREEN, led_value); - led_value = !led_value; - - TIM3->SR = 0; - - // up timeout for gas set - if (timeout == MAX_TIMEOUT) { - state = FAULT_TIMEOUT; - } else { - timeout += 1U; - } -} - -// ***************************** main code ***************************** - -void pedal(void) { - // read/write - pdl0 = adc_get_raw(ADCCHAN_ACCEL0); - pdl1 = adc_get_raw(ADCCHAN_ACCEL1); - - // write the pedal to the DAC - if (state == NO_FAULT) { - dac_set(0, MAX(gas_set_0, pdl0)); - dac_set(1, MAX(gas_set_1, pdl1)); - } else { - dac_set(0, pdl0); - dac_set(1, pdl1); - } - - watchdog_feed(); -} - -int main(void) { - // Init interrupt table - init_interrupts(true); - - REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - - // Should run at around 732Hz (see init below) - REGISTER_INTERRUPT(TIM3_IRQn, TIM3_IRQ_Handler, 1000U, FAULT_INTERRUPT_RATE_TIM3) - - disable_interrupts(); - - // init devices - clock_init(); - peripherals_init(); - detect_board_type(); - - // init board - current_board->init(); - -#ifdef PEDAL_USB - // enable USB - usb_init(); -#endif - - // pedal stuff - dac_init(); - adc_init(); - - // init can - bool llcan_speed_set = llcan_set_speed(CAN, 5000, false, false); - if (!llcan_speed_set) { - print("Failed to set llcan speed"); - } - - bool ret = llcan_init(CAN); - UNUSED(ret); - - // 48mhz / 65536 ~= 732 - timer_init(TIM3, 15); - NVIC_EnableIRQ(TIM3_IRQn); - - watchdog_init(WATCHDOG_50_MS); - - print("**** INTERRUPTS ON ****\n"); - enable_interrupts(); - - // main pedal loop - while (1) { - pedal(); - } - - return 0; -} diff --git a/panda/board/pedal/main_declarations.h b/panda/board/pedal/main_declarations.h deleted file mode 100644 index 33e4227357..0000000000 --- a/panda/board/pedal/main_declarations.h +++ /dev/null @@ -1,11 +0,0 @@ -// ******************** Prototypes ******************** -void print(const char *a); -void puth(unsigned int i); -void puth2(unsigned int i); -void puth4(unsigned int i); -typedef struct board board; -typedef struct harness_configuration harness_configuration; - -// ********************* Globals ********************** -uint8_t hw_type = 0; -const board *current_board; diff --git a/panda/board/pedal/recover.sh b/panda/board/pedal/recover.sh deleted file mode 100755 index d7fe0aff5f..0000000000 --- a/panda/board/pedal/recover.sh +++ /dev/null @@ -1,11 +0,0 @@ -#!/usr/bin/env sh -set -e - -DFU_UTIL="dfu-util" - -cd .. -scons -u -j$(nproc) -cd pedal - -$DFU_UTIL -d 0483:df11 -a 0 -s 0x08004000 -D obj/pedal.bin.signed -$DFU_UTIL -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.pedal.bin diff --git a/panda/board/power_saving.h b/panda/board/power_saving.h index 2b7d7c9872..61541cae9e 100644 --- a/panda/board/power_saving.h +++ b/panda/board/power_saving.h @@ -36,18 +36,6 @@ void set_power_save_state(int state) { current_board->enable_can_transceivers(enable); - if(current_board->has_hw_gmlan){ - // turn on GMLAN - set_gpio_output(GPIOB, 14, enable); - set_gpio_output(GPIOB, 15, enable); - } - - if(current_board->has_lin){ - // turn on LIN - set_gpio_output(GPIOB, 7, enable); - set_gpio_output(GPIOA, 14, enable); - } - // Switch off IR when in power saving if(!enable){ current_board->set_ir_power(0U); diff --git a/panda/board/provision.h b/panda/board/provision.h index e56205bffe..02768c93d0 100644 --- a/panda/board/provision.h +++ b/panda/board/provision.h @@ -3,15 +3,11 @@ #define PROVISION_CHUNK_LEN 0x20 +const char unprovisioned_text[] = "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff"; + void get_provision_chunk(uint8_t *resp) { (void)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); - if (memcmp(resp, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) == 0) { + if (memcmp(resp, unprovisioned_text, 0x20) == 0) { (void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); } } - -uint8_t chunk[PROVISION_CHUNK_LEN]; -bool is_provisioned(void) { - (void)memcpy(chunk, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); - return (memcmp(chunk, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) != 0); -} diff --git a/panda/board/safety.h b/panda/board/safety.h index a2a3e861d8..1e95244099 100644 --- a/panda/board/safety.h +++ b/panda/board/safety.h @@ -55,26 +55,32 @@ uint16_t current_safety_mode = SAFETY_SILENT; uint16_t current_safety_param = 0; const safety_hooks *current_hooks = &nooutput_hooks; -const addr_checks *current_rx_checks = &default_rx_checks; +safety_config current_safety_config; -int safety_rx_hook(CANPacket_t *to_push) { +bool safety_rx_hook(const CANPacket_t *to_push) { bool controls_allowed_prev = controls_allowed; - int ret = current_hooks->rx(to_push); + + bool valid = rx_msg_safety_check(to_push, ¤t_safety_config, current_hooks); + if (valid) { + current_hooks->rx(to_push); + } // reset mismatches on rising edge of controls_allowed to avoid rare race condition if (controls_allowed && !controls_allowed_prev) { heartbeat_engaged_mismatches = 0; } - return ret; + return valid; } -int safety_tx_hook(CANPacket_t *to_send) { - return (relay_malfunction ? -1 : current_hooks->tx(to_send)); -} +bool safety_tx_hook(CANPacket_t *to_send) { + bool whitelisted = msg_allowed(to_send, current_safety_config.tx_msgs, current_safety_config.tx_msgs_len); + if ((current_safety_mode == SAFETY_ALLOUTPUT) || (current_safety_mode == SAFETY_ELM327)) { + whitelisted = true; + } -int safety_tx_lin_hook(int lin_num, uint8_t *data, int len) { - return current_hooks->tx_lin(lin_num, data, len); + const bool safety_allowed = current_hooks->tx(to_send); + return !relay_malfunction && whitelisted && safety_allowed; } int safety_fwd_hook(int bus_num, int addr) { @@ -88,8 +94,8 @@ bool get_longitudinal_allowed(void) { // Given a CRC-8 poly, generate a static lookup table to use with a fast CRC-8 // algorithm. Called at init time for safety modes using CRC-8. void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) { - for (int i = 0; i < 256; i++) { - uint8_t crc = i; + for (uint16_t i = 0U; i <= 0xFFU; i++) { + uint8_t crc = (uint8_t)i; for (int j = 0; j < 8; j++) { if ((crc & 0x80U) != 0U) { crc = (uint8_t)((crc << 1) ^ poly); @@ -115,7 +121,7 @@ void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { } } -bool msg_allowed(CANPacket_t *to_send, const CanMsg msg_list[], int len) { +bool msg_allowed(const CANPacket_t *to_send, const CanMsg msg_list[], int len) { int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); int length = GET_LEN(to_send); @@ -130,7 +136,7 @@ bool msg_allowed(CANPacket_t *to_send, const CanMsg msg_list[], int len) { return allowed; } -int get_addr_check_index(CANPacket_t *to_push, AddrCheckStruct addr_list[], const int len) { +int get_addr_check_index(const CANPacket_t *to_push, RxCheck addr_list[], const int len) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); int length = GET_LEN(to_push); @@ -138,19 +144,19 @@ int get_addr_check_index(CANPacket_t *to_push, AddrCheckStruct addr_list[], cons int index = -1; for (int i = 0; i < len; i++) { // if multiple msgs are allowed, determine which one is present on the bus - if (!addr_list[i].msg_seen) { + if (!addr_list[i].status.msg_seen) { for (uint8_t j = 0U; (j < MAX_ADDR_CHECK_MSGS) && (addr_list[i].msg[j].addr != 0); j++) { if ((addr == addr_list[i].msg[j].addr) && (bus == addr_list[i].msg[j].bus) && (length == addr_list[i].msg[j].len)) { - addr_list[i].index = j; - addr_list[i].msg_seen = true; + addr_list[i].status.index = j; + addr_list[i].status.msg_seen = true; break; } } } - if (addr_list[i].msg_seen) { - int idx = addr_list[i].index; + if (addr_list[i].status.msg_seen) { + int idx = addr_list[i].status.index; if ((addr == addr_list[i].msg[idx].addr) && (bus == addr_list[i].msg[idx].bus) && (length == addr_list[i].msg[idx].len)) { index = i; @@ -162,22 +168,23 @@ int get_addr_check_index(CANPacket_t *to_push, AddrCheckStruct addr_list[], cons } // 1Hz safety function called by main. Now just a check for lagging safety messages -void safety_tick(const addr_checks *rx_checks) { +void safety_tick(const safety_config *cfg) { bool rx_checks_invalid = false; uint32_t ts = microsecond_timer_get(); - if (rx_checks != NULL) { - for (int i=0; i < rx_checks->len; i++) { - uint32_t elapsed_time = get_ts_elapsed(ts, rx_checks->check[i].last_timestamp); + if (cfg != NULL) { + for (int i=0; i < cfg->rx_checks_len; i++) { + uint32_t elapsed_time = get_ts_elapsed(ts, cfg->rx_checks[i].status.last_timestamp); // lag threshold is max of: 1s and MAX_MISSED_MSGS * expected timestep. // Quite conservative to not risk false triggers. // 2s of lag is worse case, since the function is called at 1Hz - bool lagging = elapsed_time > MAX(rx_checks->check[i].msg[rx_checks->check[i].index].expected_timestep * MAX_MISSED_MSGS, 1e6); - rx_checks->check[i].lagging = lagging; + uint32_t timestep = 1e6 / cfg->rx_checks[i].msg[cfg->rx_checks[i].status.index].frequency; + bool lagging = elapsed_time > MAX(timestep * MAX_MISSED_MSGS, 1e6); + cfg->rx_checks[i].status.lagging = lagging; if (lagging) { controls_allowed = false; } - if (lagging || !is_msg_valid(rx_checks->check, i)) { + if (lagging || !is_msg_valid(cfg->rx_checks, i)) { rx_checks_invalid = true; } } @@ -186,19 +193,19 @@ void safety_tick(const addr_checks *rx_checks) { safety_rx_checks_invalid = rx_checks_invalid; } -void update_counter(AddrCheckStruct addr_list[], int index, uint8_t counter) { +void update_counter(RxCheck addr_list[], int index, uint8_t counter) { if (index != -1) { - uint8_t expected_counter = (addr_list[index].last_counter + 1U) % (addr_list[index].msg[addr_list[index].index].max_counter + 1U); - addr_list[index].wrong_counters += (expected_counter == counter) ? -1 : 1; - addr_list[index].wrong_counters = CLAMP(addr_list[index].wrong_counters, 0, MAX_WRONG_COUNTERS); - addr_list[index].last_counter = counter; + uint8_t expected_counter = (addr_list[index].status.last_counter + 1U) % (addr_list[index].msg[addr_list[index].status.index].max_counter + 1U); + addr_list[index].status.wrong_counters += (expected_counter == counter) ? -1 : 1; + addr_list[index].status.wrong_counters = CLAMP(addr_list[index].status.wrong_counters, 0, MAX_WRONG_COUNTERS); + addr_list[index].status.last_counter = counter; } } -bool is_msg_valid(AddrCheckStruct addr_list[], int index) { +bool is_msg_valid(RxCheck addr_list[], int index) { bool valid = true; if (index != -1) { - if (!addr_list[index].valid_checksum || !addr_list[index].valid_quality_flag || (addr_list[index].wrong_counters >= MAX_WRONG_COUNTERS)) { + if (!addr_list[index].status.valid_checksum || !addr_list[index].status.valid_quality_flag || (addr_list[index].status.wrong_counters >= MAX_WRONG_COUNTERS)) { valid = false; controls_allowed = false; } @@ -206,49 +213,46 @@ bool is_msg_valid(AddrCheckStruct addr_list[], int index) { return valid; } -void update_addr_timestamp(AddrCheckStruct addr_list[], int index) { +void update_addr_timestamp(RxCheck addr_list[], int index) { if (index != -1) { uint32_t ts = microsecond_timer_get(); - addr_list[index].last_timestamp = ts; + addr_list[index].status.last_timestamp = ts; } } -bool addr_safety_check(CANPacket_t *to_push, - const addr_checks *rx_checks, - uint32_t (*get_checksum)(CANPacket_t *to_push), - uint32_t (*compute_checksum)(CANPacket_t *to_push), - uint8_t (*get_counter)(CANPacket_t *to_push), - bool (*get_quality_flag_valid)(CANPacket_t *to_push)) { +bool rx_msg_safety_check(const CANPacket_t *to_push, + const safety_config *cfg, + const safety_hooks *safety_hooks) { - int index = get_addr_check_index(to_push, rx_checks->check, rx_checks->len); - update_addr_timestamp(rx_checks->check, index); + int index = get_addr_check_index(to_push, cfg->rx_checks, cfg->rx_checks_len); + update_addr_timestamp(cfg->rx_checks, index); if (index != -1) { // checksum check - if ((get_checksum != NULL) && (compute_checksum != NULL) && rx_checks->check[index].msg[rx_checks->check[index].index].check_checksum) { - uint32_t checksum = get_checksum(to_push); - uint32_t checksum_comp = compute_checksum(to_push); - rx_checks->check[index].valid_checksum = checksum_comp == checksum; + if ((safety_hooks->get_checksum != NULL) && (safety_hooks->compute_checksum != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].check_checksum) { + uint32_t checksum = safety_hooks->get_checksum(to_push); + uint32_t checksum_comp = safety_hooks->compute_checksum(to_push); + cfg->rx_checks[index].status.valid_checksum = checksum_comp == checksum; } else { - rx_checks->check[index].valid_checksum = true; + cfg->rx_checks[index].status.valid_checksum = true; } // counter check (max_counter == 0 means skip check) - if ((get_counter != NULL) && (rx_checks->check[index].msg[rx_checks->check[index].index].max_counter > 0U)) { - uint8_t counter = get_counter(to_push); - update_counter(rx_checks->check, index, counter); + if ((safety_hooks->get_counter != NULL) && (cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].max_counter > 0U)) { + uint8_t counter = safety_hooks->get_counter(to_push); + update_counter(cfg->rx_checks, index, counter); } else { - rx_checks->check[index].wrong_counters = 0U; + cfg->rx_checks[index].status.wrong_counters = 0U; } // quality flag check - if ((get_quality_flag_valid != NULL) && rx_checks->check[index].msg[rx_checks->check[index].index].quality_flag) { - rx_checks->check[index].valid_quality_flag = get_quality_flag_valid(to_push); + if ((safety_hooks->get_quality_flag_valid != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].quality_flag) { + cfg->rx_checks[index].status.valid_quality_flag = safety_hooks->get_quality_flag_valid(to_push); } else { - rx_checks->check[index].valid_quality_flag = true; + cfg->rx_checks[index].status.valid_quality_flag = true; } } - return is_msg_valid(rx_checks->check, index); + return is_msg_valid(cfg->rx_checks, index); } void generic_rx_checks(bool stock_ecu_detected) { @@ -323,7 +327,7 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { // reset state set by safety mode safety_mode_cnt = 0U; relay_malfunction = false; - gas_interceptor_detected = false; + enable_gas_interceptor = false; gas_interceptor_prev = 0; gas_pressed = false; gas_pressed_prev = false; @@ -354,6 +358,11 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { relay_malfunction_reset(); safety_rx_checks_invalid = false; + current_safety_config.rx_checks = NULL; + current_safety_config.rx_checks_len = 0; + current_safety_config.tx_msgs = NULL; + current_safety_config.tx_msgs_len = 0; + int set_status = -1; // not set int hook_config_count = sizeof(safety_hook_registry) / sizeof(safety_hook_config); for (int i = 0; i < hook_config_count; i++) { @@ -365,11 +374,14 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { } } if ((set_status == 0) && (current_hooks->init != NULL)) { - current_rx_checks = current_hooks->init(param); - // reset message index and seen flags in addr struct - for (int j = 0; j < current_rx_checks->len; j++) { - current_rx_checks->check[j].index = 0; - current_rx_checks->check[j].msg_seen = false; + safety_config cfg = current_hooks->init(param); + current_safety_config.rx_checks = cfg.rx_checks; + current_safety_config.rx_checks_len = cfg.rx_checks_len; + current_safety_config.tx_msgs = cfg.tx_msgs; + current_safety_config.tx_msgs_len = cfg.tx_msgs_len; + // reset all dynamic fields in addr struct + for (int j = 0; j < current_safety_config.rx_checks_len; j++) { + current_safety_config.rx_checks[j].status = (RxStatus){0}; } } return set_status; @@ -378,7 +390,8 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { // convert a trimmed integer to signed 32 bit int int to_signed(int d, int bits) { int d_signed = d; - if (d >= (1 << MAX((bits - 1), 0))) { + int max_value = (1 << MAX((bits - 1), 0)); + if (d >= max_value) { d_signed = d - (1 << MAX(bits, 0)); } return d_signed; @@ -433,7 +446,7 @@ bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, } // check that commanded value isn't fighting against driver -bool driver_limit_check(int val, int val_last, struct sample_t *val_driver, +bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver, const int MAX_VAL, const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ALLOWANCE, const int DRIVER_FACTOR) { @@ -487,9 +500,7 @@ float interpolate(struct lookup_t xy, float x) { float dx = xy.x[i+1] - x0; float dy = xy.y[i+1] - y0; // dx should not be zero as xy.x is supposed to be monotonic - if (dx <= 0.) { - dx = 0.0001; - } + dx = MAX(dx, 0.0001); ret = (dy * (x - x0) / dx) + y0; break; } @@ -532,7 +543,7 @@ bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limit return violation; } -bool longitudinal_interceptor_checks(CANPacket_t *to_send) { +bool longitudinal_interceptor_checks(const CANPacket_t *to_send) { return !get_longitudinal_allowed() && (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)); } diff --git a/panda/board/safety/safety_body.h b/panda/board/safety/safety_body.h index 30906381e4..2ebca280f1 100644 --- a/panda/board/safety/safety_body.h +++ b/panda/board/safety/safety_body.h @@ -1,59 +1,46 @@ const CanMsg BODY_TX_MSGS[] = {{0x250, 0, 8}, {0x250, 0, 6}, {0x251, 0, 5}, // body - {0x350, 0, 8}, {0x350, 0, 6}, {0x351, 0, 5}}; // knee + {0x350, 0, 8}, {0x350, 0, 6}, {0x351, 0, 5}, // knee + {0x1, 0, 8}}; // CAN flasher -AddrCheckStruct body_addr_checks[] = { - {.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, +RxCheck body_rx_checks[] = { + {.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, }; -#define BODY_ADDR_CHECK_LEN (sizeof(body_addr_checks) / sizeof(body_addr_checks[0])) -addr_checks body_rx_checks = {body_addr_checks, BODY_ADDR_CHECK_LEN}; - -static int body_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &body_rx_checks, NULL, NULL, NULL, NULL); +static void body_rx_hook(const CANPacket_t *to_push) { // body is never at standstill vehicle_moving = true; - if (valid && (GET_ADDR(to_push) == 0x201U)) { + if (GET_ADDR(to_push) == 0x201U) { controls_allowed = true; } - - return valid; } -static int body_tx_hook(CANPacket_t *to_send) { - - int tx = 0; +static bool body_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); int len = GET_LEN(to_send); - // CAN flasher - if (addr == 0x1) { - tx = 1; - } - - if (msg_allowed(to_send, BODY_TX_MSGS, sizeof(BODY_TX_MSGS)/sizeof(BODY_TX_MSGS[0])) && controls_allowed) { - tx = 1; + if (!controls_allowed && (addr != 0x1)) { + tx = false; } // Allow going into CAN flashing mode for base & knee even if controls are not allowed bool flash_msg = ((addr == 0x250) || (addr == 0x350)) && (len == 8); if (!controls_allowed && (GET_BYTES(to_send, 0, 4) == 0xdeadfaceU) && (GET_BYTES(to_send, 4, 4) == 0x0ab00b1eU) && flash_msg) { - tx = 1; + tx = true; } return tx; } -static const addr_checks* body_init(uint16_t param) { +static safety_config body_init(uint16_t param) { UNUSED(param); - return &body_rx_checks; + return BUILD_SAFETY_CFG(body_rx_checks, BODY_TX_MSGS); } const safety_hooks body_hooks = { .init = body_init, .rx = body_rx_hook, .tx = body_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = default_fwd_hook, }; diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h index 324f73a22d..fa0e1532d5 100644 --- a/panda/board/safety/safety_chrysler.h +++ b/panda/board/safety/safety_chrysler.h @@ -93,39 +93,35 @@ const CanMsg CHRYSLER_RAM_HD_TX_MSGS[] = { {CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8}, }; -AddrCheckStruct chrysler_addr_checks[] = { - {.msg = {{CHRYSLER_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - //{.msg = {{ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}}}, - {.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_ADDRS.DAS_3, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, +RxCheck chrysler_rx_checks[] = { + {.msg = {{CHRYSLER_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + //{.msg = {{ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}}}, + {.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_ADDRS.DAS_3, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, }; -#define CHRYSLER_ADDR_CHECK_LEN (sizeof(chrysler_addr_checks) / sizeof(chrysler_addr_checks[0])) - -AddrCheckStruct chrysler_ram_dt_addr_checks[] = { - {.msg = {{CHRYSLER_RAM_DT_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + +RxCheck chrysler_ram_dt_rx_checks[] = { + {.msg = {{CHRYSLER_RAM_DT_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_DT_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_DT_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, }; -#define CHRYSLER_RAM_DT_ADDR_CHECK_LEN (sizeof(chrysler_ram_dt_addr_checks) / sizeof(chrysler_ram_dt_addr_checks[0])) - -AddrCheckStruct chrysler_ram_hd_addr_checks[] = { - {.msg = {{CHRYSLER_RAM_HD_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + +RxCheck chrysler_ram_hd_rx_checks[] = { + {.msg = {{CHRYSLER_RAM_HD_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_HD_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{CHRYSLER_RAM_HD_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, }; -#define CHRYSLER_RAM_HD_ADDR_CHECK_LEN (sizeof(chrysler_ram_hd_addr_checks) / sizeof(chrysler_ram_hd_addr_checks[0])) -addr_checks chrysler_rx_checks = {chrysler_addr_checks, CHRYSLER_ADDR_CHECK_LEN}; const uint32_t CHRYSLER_PARAM_RAM_DT = 1U; // set for Ram DT platform -const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram DT platform +const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram HD platform enum { CHRYSLER_RAM_DT, @@ -134,12 +130,12 @@ enum { } chrysler_platform = CHRYSLER_PACIFICA; const ChryslerAddrs *chrysler_addrs = &CHRYSLER_ADDRS; -static uint32_t chrysler_get_checksum(CANPacket_t *to_push) { +static uint32_t chrysler_get_checksum(const CANPacket_t *to_push) { int checksum_byte = GET_LEN(to_push) - 1U; return (uint8_t)(GET_BYTE(to_push, checksum_byte)); } -static uint32_t chrysler_compute_checksum(CANPacket_t *to_push) { +static uint32_t chrysler_compute_checksum(const CANPacket_t *to_push) { // TODO: clean this up // http://illmatics.com/Remote%20Car%20Hacking.pdf uint8_t checksum = 0xFFU; @@ -172,85 +168,67 @@ static uint32_t chrysler_compute_checksum(CANPacket_t *to_push) { return (uint8_t)(~checksum); } -static uint8_t chrysler_get_counter(CANPacket_t *to_push) { +static uint8_t chrysler_get_counter(const CANPacket_t *to_push) { return (uint8_t)(GET_BYTE(to_push, 6) >> 4); } -static int chrysler_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &chrysler_rx_checks, - chrysler_get_checksum, chrysler_compute_checksum, - chrysler_get_counter, NULL); - +static void chrysler_rx_hook(const CANPacket_t *to_push) { const int bus = GET_BUS(to_push); const int addr = GET_ADDR(to_push); - if (valid) { - - // Measured EPS torque - if ((bus == 0) && (addr == chrysler_addrs->EPS_2)) { - int torque_meas_new = ((GET_BYTE(to_push, 4) & 0x7U) << 8) + GET_BYTE(to_push, 5) - 1024U; - update_sample(&torque_meas, torque_meas_new); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - const int das_3_bus = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 2; - if ((bus == das_3_bus) && (addr == chrysler_addrs->DAS_3)) { - bool cruise_engaged = GET_BIT(to_push, 21U) == 1U; - pcm_cruise_check(cruise_engaged); - } + // Measured EPS torque + if ((bus == 0) && (addr == chrysler_addrs->EPS_2)) { + int torque_meas_new = ((GET_BYTE(to_push, 4) & 0x7U) << 8) + GET_BYTE(to_push, 5) - 1024U; + update_sample(&torque_meas, torque_meas_new); + } - // TODO: use the same message for both - // update vehicle moving - if ((chrysler_platform != CHRYSLER_PACIFICA) && (bus == 0) && (addr == chrysler_addrs->ESP_8)) { - vehicle_moving = ((GET_BYTE(to_push, 4) << 8) + GET_BYTE(to_push, 5)) != 0U; - } - if ((chrysler_platform == CHRYSLER_PACIFICA) && (bus == 0) && (addr == 514)) { - int speed_l = (GET_BYTE(to_push, 0) << 4) + (GET_BYTE(to_push, 1) >> 4); - int speed_r = (GET_BYTE(to_push, 2) << 4) + (GET_BYTE(to_push, 3) >> 4); - vehicle_moving = (speed_l != 0) || (speed_r != 0); - } + // enter controls on rising edge of ACC, exit controls on ACC off + const int das_3_bus = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 2; + if ((bus == das_3_bus) && (addr == chrysler_addrs->DAS_3)) { + bool cruise_engaged = GET_BIT(to_push, 21U); + pcm_cruise_check(cruise_engaged); + } - // exit controls on rising edge of gas press - if ((bus == 0) && (addr == chrysler_addrs->ECM_5)) { - gas_pressed = GET_BYTE(to_push, 0U) != 0U; - } + // TODO: use the same message for both + // update vehicle moving + if ((chrysler_platform != CHRYSLER_PACIFICA) && (bus == 0) && (addr == chrysler_addrs->ESP_8)) { + vehicle_moving = ((GET_BYTE(to_push, 4) << 8) + GET_BYTE(to_push, 5)) != 0U; + } + if ((chrysler_platform == CHRYSLER_PACIFICA) && (bus == 0) && (addr == 514)) { + int speed_l = (GET_BYTE(to_push, 0) << 4) + (GET_BYTE(to_push, 1) >> 4); + int speed_r = (GET_BYTE(to_push, 2) << 4) + (GET_BYTE(to_push, 3) >> 4); + vehicle_moving = (speed_l != 0) || (speed_r != 0); + } - // exit controls on rising edge of brake press - if ((bus == 0) && (addr == chrysler_addrs->ESP_1)) { - brake_pressed = ((GET_BYTE(to_push, 0U) & 0xFU) >> 2U) == 1U; - } + // exit controls on rising edge of gas press + if ((bus == 0) && (addr == chrysler_addrs->ECM_5)) { + gas_pressed = GET_BYTE(to_push, 0U) != 0U; + } - generic_rx_checks((bus == 0) && (addr == chrysler_addrs->LKAS_COMMAND)); + // exit controls on rising edge of brake press + if ((bus == 0) && (addr == chrysler_addrs->ESP_1)) { + brake_pressed = ((GET_BYTE(to_push, 0U) & 0xFU) >> 2U) == 1U; } - return valid; -} -static int chrysler_tx_hook(CANPacket_t *to_send) { + generic_rx_checks((bus == 0) && (addr == chrysler_addrs->LKAS_COMMAND)); +} - int tx = 1; +static bool chrysler_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); - if (chrysler_platform == CHRYSLER_RAM_DT) { - tx = msg_allowed(to_send, CHRYSLER_RAM_DT_TX_MSGS, sizeof(CHRYSLER_RAM_DT_TX_MSGS) / sizeof(CHRYSLER_RAM_DT_TX_MSGS[0])); - } else if (chrysler_platform == CHRYSLER_RAM_HD) { - tx = msg_allowed(to_send, CHRYSLER_RAM_HD_TX_MSGS, sizeof(CHRYSLER_RAM_HD_TX_MSGS) / sizeof(CHRYSLER_RAM_HD_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, CHRYSLER_TX_MSGS, sizeof(CHRYSLER_TX_MSGS) / sizeof(CHRYSLER_TX_MSGS[0])); - } - // STEERING - if (tx && (addr == chrysler_addrs->LKAS_COMMAND)) { + if (addr == chrysler_addrs->LKAS_COMMAND) { int start_byte = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 1; int desired_torque = ((GET_BYTE(to_send, start_byte) & 0x7U) << 8) | GET_BYTE(to_send, start_byte + 1); desired_torque -= 1024; const SteeringLimits limits = (chrysler_platform == CHRYSLER_PACIFICA) ? CHRYSLER_STEERING_LIMITS : (chrysler_platform == CHRYSLER_RAM_DT) ? CHRYSLER_RAM_DT_STEERING_LIMITS : CHRYSLER_RAM_HD_STEERING_LIMITS; - - bool steer_req = (chrysler_platform == CHRYSLER_PACIFICA) ? (GET_BIT(to_send, 4U) != 0U) : ((GET_BYTE(to_send, 3) & 0x7U) == 2U); + + bool steer_req = (chrysler_platform == CHRYSLER_PACIFICA) ? GET_BIT(to_send, 4U) : (GET_BYTE(to_send, 3) & 0x7U) == 2U; if (steer_torque_cmd_checks(desired_torque, steer_req, limits)) { - tx = 0; + tx = false; } } @@ -260,7 +238,7 @@ static int chrysler_tx_hook(CANPacket_t *to_send) { const bool is_resume = GET_BYTE(to_send, 0) == 0x10U; const bool allowed = is_cancel || (is_resume && controls_allowed); if (!allowed) { - tx = 0; + tx = false; } } @@ -284,30 +262,34 @@ static int chrysler_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* chrysler_init(uint16_t param) { - if (GET_FLAG(param, CHRYSLER_PARAM_RAM_DT)) { +static safety_config chrysler_init(uint16_t param) { + safety_config ret; + + bool enable_ram_dt = GET_FLAG(param, CHRYSLER_PARAM_RAM_DT); + if (enable_ram_dt) { chrysler_platform = CHRYSLER_RAM_DT; chrysler_addrs = &CHRYSLER_RAM_DT_ADDRS; - chrysler_rx_checks = (addr_checks){chrysler_ram_dt_addr_checks, CHRYSLER_RAM_DT_ADDR_CHECK_LEN}; - } else if (GET_FLAG(param, CHRYSLER_PARAM_RAM_HD)) { + ret = BUILD_SAFETY_CFG(chrysler_ram_dt_rx_checks, CHRYSLER_RAM_DT_TX_MSGS); #ifdef ALLOW_DEBUG + } else if (GET_FLAG(param, CHRYSLER_PARAM_RAM_HD)) { chrysler_platform = CHRYSLER_RAM_HD; chrysler_addrs = &CHRYSLER_RAM_HD_ADDRS; - chrysler_rx_checks = (addr_checks){chrysler_ram_hd_addr_checks, CHRYSLER_RAM_HD_ADDR_CHECK_LEN}; + ret = BUILD_SAFETY_CFG(chrysler_ram_hd_rx_checks, CHRYSLER_RAM_HD_TX_MSGS); #endif } else { chrysler_platform = CHRYSLER_PACIFICA; chrysler_addrs = &CHRYSLER_ADDRS; - chrysler_rx_checks = (addr_checks){chrysler_addr_checks, CHRYSLER_ADDR_CHECK_LEN}; + ret = BUILD_SAFETY_CFG(chrysler_rx_checks, CHRYSLER_TX_MSGS); } - - return &chrysler_rx_checks; + return ret; } const safety_hooks chrysler_hooks = { .init = chrysler_init, .rx = chrysler_rx_hook, .tx = chrysler_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = chrysler_fwd_hook, + .get_counter = chrysler_get_counter, + .get_checksum = chrysler_get_checksum, + .compute_checksum = chrysler_compute_checksum, }; diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 90c8a0655d..6c47dba3d6 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -1,32 +1,19 @@ -const addr_checks default_rx_checks = { - .check = NULL, - .len = 0, -}; - -int default_rx_hook(CANPacket_t *to_push) { +void default_rx_hook(const CANPacket_t *to_push) { UNUSED(to_push); - return true; } // *** no output safety mode *** -static const addr_checks* nooutput_init(uint16_t param) { +static safety_config nooutput_init(uint16_t param) { UNUSED(param); - return &default_rx_checks; + return (safety_config){NULL, 0, NULL, 0}; } -static int nooutput_tx_hook(CANPacket_t *to_send) { +static bool nooutput_tx_hook(const CANPacket_t *to_send) { UNUSED(to_send); return false; } -static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { - UNUSED(lin_num); - UNUSED(data); - UNUSED(len); - return false; -} - static int default_fwd_hook(int bus_num, int addr) { UNUSED(bus_num); UNUSED(addr); @@ -37,7 +24,6 @@ const safety_hooks nooutput_hooks = { .init = nooutput_init, .rx = default_rx_hook, .tx = nooutput_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = default_fwd_hook, }; @@ -47,24 +33,17 @@ const safety_hooks nooutput_hooks = { const uint16_t ALLOUTPUT_PARAM_PASSTHROUGH = 1; bool alloutput_passthrough = false; -static const addr_checks* alloutput_init(uint16_t param) { +static safety_config alloutput_init(uint16_t param) { controls_allowed = true; alloutput_passthrough = GET_FLAG(param, ALLOUTPUT_PARAM_PASSTHROUGH); - return &default_rx_checks; + return (safety_config){NULL, 0, NULL, 0}; } -static int alloutput_tx_hook(CANPacket_t *to_send) { +static bool alloutput_tx_hook(const CANPacket_t *to_send) { UNUSED(to_send); return true; } -static int alloutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { - UNUSED(lin_num); - UNUSED(data); - UNUSED(len); - return true; -} - static int alloutput_fwd_hook(int bus_num, int addr) { int bus_fwd = -1; UNUSED(addr); @@ -85,6 +64,5 @@ const safety_hooks alloutput_hooks = { .init = alloutput_init, .rx = default_rx_hook, .tx = alloutput_tx_hook, - .tx_lin = alloutput_tx_lin_hook, .fwd = alloutput_fwd_hook, }; diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h index 6b1e72eac3..954efca8d5 100644 --- a/panda/board/safety/safety_elm327.h +++ b/panda/board/safety/safety_elm327.h @@ -1,34 +1,29 @@ -static int elm327_tx_hook(CANPacket_t *to_send) { +const int GM_CAMERA_DIAG_ADDR = 0x24B; - int tx = 1; +static bool elm327_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); int len = GET_LEN(to_send); - //All ISO 15765-4 messages must be 8 bytes long + // All ISO 15765-4 messages must be 8 bytes long if (len != 8) { - tx = 0; + tx = false; } - //Check valid 29 bit send addresses for ISO 15765-4 - //Check valid 11 bit send addresses for ISO 15765-4 + // Check valid 29 bit send addresses for ISO 15765-4 + // Check valid 11 bit send addresses for ISO 15765-4 if ((addr != 0x18DB33F1) && ((addr & 0x1FFF00FF) != 0x18DA00F1) && - ((addr & 0x1FFFFF00) != 0x600) && ((addr & 0x1FFFFF00) != 0x700)) { - tx = 0; + ((addr & 0x1FFFFF00) != 0x600) && ((addr & 0x1FFFFF00) != 0x700) && + (addr != GM_CAMERA_DIAG_ADDR)) { + tx = false; } - return tx; -} -static int elm327_tx_lin_hook(int lin_num, uint8_t *data, int len) { - int tx = 1; - if (lin_num != 0) { - tx = 0; //Only operate on LIN 0, aka serial 2 - } - if ((len < 5) || (len > 11)) { - tx = 0; //Valid KWP size - } - if (!(((data[0] & 0xF8U) == 0xC0U) && ((data[0] & 0x07U) != 0U) && - (data[1] == 0x33U) && (data[2] == 0xF1U))) { - tx = 0; //Bad msg + // GM camera uses non-standard diagnostic address, this has no control message address collisions + if ((addr == GM_CAMERA_DIAG_ADDR) && (len == 8)) { + // Only allow known frame types for ISO 15765-2 + if ((GET_BYTE(to_send, 0) & 0xF0U) > 0x30U) { + tx = false; + } } return tx; } @@ -38,6 +33,5 @@ const safety_hooks elm327_hooks = { .init = nooutput_init, .rx = default_rx_hook, .tx = elm327_tx_hook, - .tx_lin = elm327_tx_lin_hook, .fwd = default_fwd_hook, }; diff --git a/panda/board/safety/safety_ford.h b/panda/board/safety/safety_ford.h index 4a1825f087..2f11863b49 100644 --- a/panda/board/safety/safety_ford.h +++ b/panda/board/safety/safety_ford.h @@ -25,7 +25,6 @@ const CanMsg FORD_STOCK_TX_MSGS[] = { {FORD_LateralMotionControl, 0, 8}, {FORD_IPMA_Data, 0, 8}, }; -#define FORD_STOCK_TX_LEN (sizeof(FORD_STOCK_TX_MSGS) / sizeof(FORD_STOCK_TX_MSGS[0])) const CanMsg FORD_LONG_TX_MSGS[] = { {FORD_Steering_Data_FD1, 0, 8}, @@ -36,7 +35,6 @@ const CanMsg FORD_LONG_TX_MSGS[] = { {FORD_LateralMotionControl, 0, 8}, {FORD_IPMA_Data, 0, 8}, }; -#define FORD_LONG_TX_LEN (sizeof(FORD_LONG_TX_MSGS) / sizeof(FORD_LONG_TX_MSGS[0])) const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = { {FORD_Steering_Data_FD1, 0, 8}, @@ -46,7 +44,6 @@ const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = { {FORD_LateralMotionControl2, 0, 8}, {FORD_IPMA_Data, 0, 8}, }; -#define FORD_CANFD_STOCK_TX_LEN (sizeof(FORD_CANFD_STOCK_TX_MSGS) / sizeof(FORD_CANFD_STOCK_TX_MSGS[0])) const CanMsg FORD_CANFD_LONG_TX_MSGS[] = { {FORD_Steering_Data_FD1, 0, 8}, @@ -57,24 +54,21 @@ const CanMsg FORD_CANFD_LONG_TX_MSGS[] = { {FORD_LateralMotionControl2, 0, 8}, {FORD_IPMA_Data, 0, 8}, }; -#define FORD_CANFD_LONG_TX_LEN (sizeof(FORD_CANFD_LONG_TX_MSGS) / sizeof(FORD_CANFD_LONG_TX_MSGS[0])) // warning: quality flags are not yet checked in openpilot's CAN parser, // this may be the cause of blocked messages -AddrCheckStruct ford_addr_checks[] = { - {.msg = {{FORD_BrakeSysFeatures, 0, 8, .check_checksum = true, .max_counter = 15U, .quality_flag=true, .expected_timestep = 20000U}, { 0 }, { 0 }}}, +RxCheck ford_rx_checks[] = { + {.msg = {{FORD_BrakeSysFeatures, 0, 8, .check_checksum = true, .max_counter = 15U, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}}, // TODO: FORD_EngVehicleSpThrottle2 has a counter that skips by 2, understand and enable counter check - {.msg = {{FORD_EngVehicleSpThrottle2, 0, 8, .check_checksum = true, .quality_flag=true, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{FORD_Yaw_Data_FD1, 0, 8, .check_checksum = true, .max_counter = 255U, .quality_flag=true, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{FORD_EngVehicleSpThrottle2, 0, 8, .check_checksum = true, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{FORD_Yaw_Data_FD1, 0, 8, .check_checksum = true, .max_counter = 255U, .quality_flag=true, .frequency = 100U}, { 0 }, { 0 }}}, // These messages have no counter or checksum - {.msg = {{FORD_EngBrakeData, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{FORD_EngVehicleSpThrottle, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{FORD_DesiredTorqBrk, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{FORD_EngBrakeData, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{FORD_EngVehicleSpThrottle, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{FORD_DesiredTorqBrk, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, }; -#define FORD_ADDR_CHECK_LEN (sizeof(ford_addr_checks) / sizeof(ford_addr_checks[0])) -addr_checks ford_rx_checks = {ford_addr_checks, FORD_ADDR_CHECK_LEN}; -static uint8_t ford_get_counter(CANPacket_t *to_push) { +static uint8_t ford_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t cnt = 0; @@ -89,7 +83,7 @@ static uint8_t ford_get_counter(CANPacket_t *to_push) { return cnt; } -static uint32_t ford_get_checksum(CANPacket_t *to_push) { +static uint32_t ford_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -107,7 +101,7 @@ static uint32_t ford_get_checksum(CANPacket_t *to_push) { return chksum; } -static uint32_t ford_compute_checksum(CANPacket_t *to_push) { +static uint32_t ford_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -134,7 +128,7 @@ static uint32_t ford_compute_checksum(CANPacket_t *to_push) { return chksum; } -static bool ford_get_quality_flag_valid(CANPacket_t *to_push) { +static bool ford_get_quality_flag_valid(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); bool valid = false; @@ -163,7 +157,7 @@ const LongitudinalLimits FORD_LONG_LIMITS = { .inactive_accel = 5128, // -0.0008 m/s^2 // gas cmd limits - // Signal: AccPrpl_A_Rq + // Signal: AccPrpl_A_Rq & AccPrpl_A_Pred .max_gas = 700, // 2.0 m/s^2 .min_gas = 450, // -0.5 m/s^2 .inactive_gas = 0, // -5.0 m/s^2 @@ -207,23 +201,20 @@ const SteeringLimits FORD_STEERING_LIMITS = { .inactive_angle_is_zero = true, }; -static int ford_rx_hook(CANPacket_t *to_push) { - bool valid = addr_safety_check(to_push, &ford_rx_checks, - ford_get_checksum, ford_compute_checksum, ford_get_counter, ford_get_quality_flag_valid); - - if (valid && (GET_BUS(to_push) == FORD_MAIN_BUS)) { +static void ford_rx_hook(const CANPacket_t *to_push) { + if (GET_BUS(to_push) == FORD_MAIN_BUS) { int addr = GET_ADDR(to_push); // Update in motion state from standstill signal if (addr == FORD_DesiredTorqBrk) { // Signal: VehStop_D_Stat - vehicle_moving = ((GET_BYTE(to_push, 3) >> 3) & 0x3U) == 0U; + vehicle_moving = ((GET_BYTE(to_push, 3) >> 3) & 0x3U) != 1U; } // Update vehicle speed if (addr == FORD_BrakeSysFeatures) { // Signal: Veh_V_ActlBrk - update_sample(&vehicle_speed, ROUND(((GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1)) * 0.01 / 3.6 * VEHICLE_SPEED_FACTOR)); + UPDATE_VEHICLE_SPEED(((GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1)) * 0.01 / 3.6); } // Check vehicle speed against a second source @@ -231,7 +222,8 @@ static int ford_rx_hook(CANPacket_t *to_push) { // Disable controls if speeds from ABS and PCM ECUs are too far apart. // Signal: Veh_V_ActlEng float filtered_pcm_speed = ((GET_BYTE(to_push, 6) << 8) | GET_BYTE(to_push, 7)) * 0.01 / 3.6; - if (ABS(filtered_pcm_speed - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > FORD_MAX_SPEED_DELTA) { + bool is_invalid_speed = ABS(filtered_pcm_speed - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > FORD_MAX_SPEED_DELTA; + if (is_invalid_speed) { controls_allowed = false; } } @@ -272,44 +264,34 @@ static int ford_rx_hook(CANPacket_t *to_push) { generic_rx_checks(stock_ecu_detected); } - return valid; } -static int ford_tx_hook(CANPacket_t *to_send) { +static bool ford_tx_hook(const CANPacket_t *to_send) { + bool tx = true; + int addr = GET_ADDR(to_send); - int tx; - if (ford_canfd) { - if (ford_longitudinal) { - tx = msg_allowed(to_send, FORD_CANFD_LONG_TX_MSGS, FORD_CANFD_LONG_TX_LEN); - } else { - tx = msg_allowed(to_send, FORD_CANFD_STOCK_TX_MSGS, FORD_CANFD_STOCK_TX_LEN); - } - } else { - if (ford_longitudinal) { - tx = msg_allowed(to_send, FORD_LONG_TX_MSGS, FORD_LONG_TX_LEN); - } else { - tx = msg_allowed(to_send, FORD_STOCK_TX_MSGS, FORD_STOCK_TX_LEN); - } - } // Safety check for ACCDATA accel and brake requests if (addr == FORD_ACCDATA) { // Signal: AccPrpl_A_Rq int gas = ((GET_BYTE(to_send, 6) & 0x3U) << 8) | GET_BYTE(to_send, 7); + // Signal: AccPrpl_A_Pred + int gas_pred = ((GET_BYTE(to_send, 2) & 0x3U) << 8) | GET_BYTE(to_send, 3); // Signal: AccBrkTot_A_Rq int accel = ((GET_BYTE(to_send, 0) & 0x1FU) << 8) | GET_BYTE(to_send, 1); // Signal: CmbbDeny_B_Actl - int cmbb_deny = GET_BIT(to_send, 37U); + bool cmbb_deny = GET_BIT(to_send, 37U); bool violation = false; violation |= longitudinal_accel_checks(accel, FORD_LONG_LIMITS); violation |= longitudinal_gas_checks(gas, FORD_LONG_LIMITS); + violation |= longitudinal_gas_checks(gas_pred, FORD_LONG_LIMITS); // Safety check for stock AEB - violation |= cmbb_deny != 0; // do not prevent stock AEB actuation + violation |= cmbb_deny; // do not prevent stock AEB actuation if (violation) { - tx = 0; + tx = false; } } @@ -320,11 +302,11 @@ static int ford_tx_hook(CANPacket_t *to_send) { // Violation if resume button is pressed while controls not allowed, or // if cancel button is pressed when cruise isn't engaged. bool violation = false; - violation |= (GET_BIT(to_send, 8U) == 1U) && !cruise_engaged_prev; // Signal: CcAslButtnCnclPress (cancel) - violation |= (GET_BIT(to_send, 25U) == 1U) && !controls_allowed; // Signal: CcAsllButtnResPress (resume) + violation |= GET_BIT(to_send, 8U) && !cruise_engaged_prev; // Signal: CcAslButtnCnclPress (cancel) + violation |= GET_BIT(to_send, 25U) && !controls_allowed; // Signal: CcAsllButtnResPress (resume) if (violation) { - tx = 0; + tx = false; } } @@ -336,7 +318,7 @@ static int ford_tx_hook(CANPacket_t *to_send) { // but the action (LkaActvStats_D2_Req) must be set to zero. unsigned int action = GET_BYTE(to_send, 0) >> 5; if (action != 0U) { - tx = 0; + tx = false; } } @@ -357,7 +339,7 @@ static int ford_tx_hook(CANPacket_t *to_send) { violation |= steer_angle_cmd_checks(desired_curvature, steer_control_enabled, FORD_STEERING_LIMITS); if (violation) { - tx = 0; + tx = false; } } @@ -378,11 +360,10 @@ static int ford_tx_hook(CANPacket_t *to_send) { violation |= steer_angle_cmd_checks(desired_curvature, steer_control_enabled, FORD_STEERING_LIMITS); if (violation) { - tx = 0; + tx = false; } } - // 1 allows the message through return tx; } @@ -418,19 +399,31 @@ static int ford_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* ford_init(uint16_t param) { +static safety_config ford_init(uint16_t param) { UNUSED(param); #ifdef ALLOW_DEBUG ford_longitudinal = GET_FLAG(param, FORD_PARAM_LONGITUDINAL); ford_canfd = GET_FLAG(param, FORD_PARAM_CANFD); #endif - return &ford_rx_checks; + + safety_config ret; + if (ford_canfd) { + ret = ford_longitudinal ? BUILD_SAFETY_CFG(ford_rx_checks, FORD_CANFD_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(ford_rx_checks, FORD_CANFD_STOCK_TX_MSGS); + } else { + ret = ford_longitudinal ? BUILD_SAFETY_CFG(ford_rx_checks, FORD_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(ford_rx_checks, FORD_STOCK_TX_MSGS); + } + return ret; } const safety_hooks ford_hooks = { .init = ford_init, .rx = ford_rx_hook, .tx = ford_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = ford_fwd_hook, + .get_counter = ford_get_counter, + .get_checksum = ford_get_checksum, + .compute_checksum = ford_compute_checksum, + .get_quality_flag_valid = ford_get_quality_flag_valid, }; diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h index 82c154765a..82a5d9cd3e 100644 --- a/panda/board/safety/safety_gm.h +++ b/panda/board/safety/safety_gm.h @@ -39,18 +39,16 @@ const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x315, 0, 5}, {0x2CB, 0, 8 {0x184, 2, 8}}; // camera bus // TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. -AddrCheckStruct gm_addr_checks[] = { - {.msg = {{0x184, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{0x34A, 0, 5, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{0x1E1, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{0xBE, 0, 6, .expected_timestep = 100000U}, // Volt, Silverado, Acadia Denali - {0xBE, 0, 7, .expected_timestep = 100000U}, // Bolt EUV - {0xBE, 0, 8, .expected_timestep = 100000U}}}, // Escalade - {.msg = {{0x1C4, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{0xC9, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, +RxCheck gm_rx_checks[] = { + {.msg = {{0x184, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{0x34A, 0, 5, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{0x1E1, 0, 7, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{0xBE, 0, 6, .frequency = 10U}, // Volt, Silverado, Acadia Denali + {0xBE, 0, 7, .frequency = 10U}, // Bolt EUV + {0xBE, 0, 8, .frequency = 10U}}}, // Escalade + {.msg = {{0x1C4, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{0xC9, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, }; -#define GM_RX_CHECK_LEN (sizeof(gm_addr_checks) / sizeof(gm_addr_checks[0])) -addr_checks gm_rx_checks = {gm_addr_checks, GM_RX_CHECK_LEN}; const uint16_t GM_PARAM_HW_CAM = 1; const uint16_t GM_PARAM_HW_CAM_LONG = 2; @@ -66,11 +64,8 @@ enum {GM_ASCM, GM_CAM} gm_hw = GM_ASCM; bool gm_cam_long = false; bool gm_pcm_cruise = false; -static int gm_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &gm_rx_checks, NULL, NULL, NULL, NULL); - - if (valid && (GET_BUS(to_push) == 0U)) { +static void gm_rx_hook(const CANPacket_t *to_push) { + if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); if (addr == 0x184) { @@ -113,7 +108,7 @@ static int gm_rx_hook(CANPacket_t *to_push) { } if ((addr == 0xC9) && (gm_hw == GM_CAM)) { - brake_pressed = GET_BIT(to_push, 40U) != 0U; + brake_pressed = GET_BIT(to_push, 40U); } if (addr == 0x1C4) { @@ -138,36 +133,18 @@ static int gm_rx_hook(CANPacket_t *to_push) { } generic_rx_checks(stock_ecu_detected); } - return valid; } -// all commands: gas/regen, friction brake and steering -// if controls_allowed and no pedals pressed -// allow all commands up to limit -// else -// block all commands that produce actuation - -static int gm_tx_hook(CANPacket_t *to_send) { - - int tx = 1; +static bool gm_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); - if (gm_hw == GM_CAM) { - if (gm_cam_long) { - tx = msg_allowed(to_send, GM_CAM_LONG_TX_MSGS, sizeof(GM_CAM_LONG_TX_MSGS)/sizeof(GM_CAM_LONG_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, GM_CAM_TX_MSGS, sizeof(GM_CAM_TX_MSGS)/sizeof(GM_CAM_TX_MSGS[0])); - } - } else { - tx = msg_allowed(to_send, GM_ASCM_TX_MSGS, sizeof(GM_ASCM_TX_MSGS)/sizeof(GM_ASCM_TX_MSGS[0])); - } - // BRAKE: safety check if (addr == 0x315) { int brake = ((GET_BYTE(to_send, 0) & 0xFU) << 8) + GET_BYTE(to_send, 1); brake = (0x1000 - brake) & 0xFFF; if (longitudinal_brake_checks(brake, *gm_long_limits)) { - tx = 0; + tx = false; } } @@ -176,16 +153,16 @@ static int gm_tx_hook(CANPacket_t *to_send) { int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1); desired_torque = to_signed(desired_torque, 11); - bool steer_req = (GET_BIT(to_send, 3U) != 0U); + bool steer_req = GET_BIT(to_send, 3U); if (steer_torque_cmd_checks(desired_torque, steer_req, GM_STEERING_LIMITS)) { - tx = 0; + tx = false; } } // GAS/REGEN: safety check if (addr == 0x2CB) { - bool apply = GET_BIT(to_send, 0U) != 0U; + bool apply = GET_BIT(to_send, 0U); int gas_regen = ((GET_BYTE(to_send, 2) & 0x7FU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3); bool violation = false; @@ -194,7 +171,7 @@ static int gm_tx_hook(CANPacket_t *to_send) { violation |= longitudinal_gas_checks(gas_regen, *gm_long_limits); if (violation) { - tx = 0; + tx = false; } } @@ -204,16 +181,14 @@ static int gm_tx_hook(CANPacket_t *to_send) { bool allowed_cancel = (button == 6) && cruise_engaged_prev; if (!allowed_cancel) { - tx = 0; + tx = false; } } - // 1 allows the message through return tx; } static int gm_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; if (gm_hw == GM_CAM) { @@ -229,7 +204,7 @@ static int gm_fwd_hook(int bus_num, int addr) { // block lkas message and acc messages if gm_cam_long, forward all others bool is_lkas_msg = (addr == 0x180); bool is_acc_msg = (addr == 0x315) || (addr == 0x2CB) || (addr == 0x370); - int block_msg = is_lkas_msg || (is_acc_msg && gm_cam_long); + bool block_msg = is_lkas_msg || (is_acc_msg && gm_cam_long); if (!block_msg) { bus_fwd = 0; } @@ -239,7 +214,7 @@ static int gm_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* gm_init(uint16_t param) { +static safety_config gm_init(uint16_t param) { gm_hw = GET_FLAG(param, GM_PARAM_HW_CAM) ? GM_CAM : GM_ASCM; if (gm_hw == GM_ASCM) { @@ -253,13 +228,17 @@ static const addr_checks* gm_init(uint16_t param) { gm_cam_long = GET_FLAG(param, GM_PARAM_HW_CAM_LONG); #endif gm_pcm_cruise = (gm_hw == GM_CAM) && !gm_cam_long; - return &gm_rx_checks; + + safety_config ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_ASCM_TX_MSGS); + if (gm_hw == GM_CAM) { + ret = gm_cam_long ? BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_LONG_TX_MSGS) : BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_TX_MSGS); + } + return ret; } const safety_hooks gm_hooks = { .init = gm_init, .rx = gm_rx_hook, .tx = gm_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = gm_fwd_hook, }; diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index 415a379076..78bbb7f0bf 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -1,12 +1,5 @@ -// board enforces -// in-state -// accel set/resume -// out-state -// cancel button -// accel rising edge -// brake rising edge -// brake > 0mph -const CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x200, 0, 6}, {0x30C, 0, 8}, {0x33D, 0, 5}}; +const CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x30C, 0, 8}, {0x33D, 0, 5}}; +const CanMsg HONDA_N_INTERCEPTOR_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x200, 0, 6}, {0x30C, 0, 8}, {0x33D, 0, 5}}; const CanMsg HONDA_BOSCH_TX_MSGS[] = {{0xE4, 0, 5}, {0xE5, 0, 8}, {0x296, 1, 4}, {0x33D, 0, 5}, {0x33DA, 0, 5}, {0x33DB, 0, 8}}; // Bosch const CanMsg HONDA_BOSCH_LONG_TX_MSGS[] = {{0xE4, 1, 5}, {0x1DF, 1, 8}, {0x1EF, 1, 8}, {0x1FA, 1, 8}, {0x30C, 1, 8}, {0x33D, 1, 5}, {0x33DA, 1, 5}, {0x33DB, 1, 8}, {0x39F, 1, 8}, {0x18DAB0F1, 1, 8}}; // Bosch w/ gas and brakes const CanMsg HONDA_RADARLESS_TX_MSGS[] = {{0xE4, 0, 5}, {0x296, 2, 4}, {0x33D, 0, 8}}; // Bosch radarless @@ -33,40 +26,62 @@ const LongitudinalLimits HONDA_NIDEC_LONG_LIMITS = { .inactive_speed = 0, }; +// All common address checks except SCM_BUTTONS which isn't on one Nidec safety configuration +#define HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \ + {.msg = {{0x1A6, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 25U}, /* SCM_BUTTONS */ \ + {0x296, (pt_bus), 4, .check_checksum = true, .max_counter = 3U, .frequency = 25U}, { 0 }}}, \ + {.msg = {{0x158, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, { 0 }, { 0 }}}, /* ENGINE_DATA */ \ + {.msg = {{0x17C, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, { 0 }, { 0 }}}, /* POWERTRAIN_DATA */ \ + +#define HONDA_COMMON_RX_CHECKS(pt_bus) \ + HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \ + {.msg = {{0x326, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 10U}, { 0 }, { 0 }}}, /* SCM_FEEDBACK */ \ + +// Alternate brake message is used on some Honda Bosch, and Honda Bosch radarless (where PT bus is 0) +#define HONDA_ALT_BRAKE_ADDR_CHECK(pt_bus) \ + {.msg = {{0x1BE, (pt_bus), 3, .check_checksum = true, .max_counter = 3U, .frequency = 50U}, { 0 }, { 0 }}}, /* BRAKE_MODULE */ \ + + // Nidec and bosch radarless has the powertrain bus on bus 0 -AddrCheckStruct honda_common_addr_checks[] = { - {.msg = {{0x1A6, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, // SCM_BUTTONS - {0x296, 0, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, { 0 }}}, - {.msg = {{0x158, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // ENGINE_DATA - {.msg = {{0x17C, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, // POWERTRAIN_DATA - {0x1BE, 0, 3, .check_checksum = true, .max_counter = 3U, .expected_timestep = 20000U}, { 0 }}}, // BRAKE_MODULE (for bosch radarless) - {.msg = {{0x326, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // SCM_FEEDBACK +RxCheck honda_common_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(0) }; -#define HONDA_COMMON_ADDR_CHECKS_LEN (sizeof(honda_common_addr_checks) / sizeof(honda_common_addr_checks[0])) - -// For Nidecs with main on signal on an alternate msg -AddrCheckStruct honda_nidec_alt_addr_checks[] = { - {.msg = {{0x1A6, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, - {0x296, 0, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, { 0 }}}, - {.msg = {{0x158, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{0x17C, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + +RxCheck honda_common_interceptor_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(0) + {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, +}; + +RxCheck honda_common_alt_brake_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(0) + HONDA_ALT_BRAKE_ADDR_CHECK(0) }; -#define HONDA_NIDEC_ALT_ADDR_CHECKS_LEN (sizeof(honda_nidec_alt_addr_checks) / sizeof(honda_nidec_alt_addr_checks[0])) - -// Bosch has pt on bus 1 -AddrCheckStruct honda_bosch_addr_checks[] = { - {.msg = {{0x296, 1, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, { 0 }, { 0 }}}, - {.msg = {{0x158, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{0x17C, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, - {0x1BE, 1, 3, .check_checksum = true, .max_counter = 3U, .expected_timestep = 20000U}, { 0 }}}, - {.msg = {{0x326, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + +// For Nidecs with main on signal on an alternate msg (missing 0x326) +RxCheck honda_nidec_alt_rx_checks[] = { + HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0) +}; + +RxCheck honda_nidec_alt_interceptor_rx_checks[] = { + HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0) + {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, +}; + +// Bosch has pt on bus 1, verified 0x1A6 does not exist +RxCheck honda_bosch_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(1) +}; + +RxCheck honda_bosch_alt_brake_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(1) + HONDA_ALT_BRAKE_ADDR_CHECK(1) }; -#define HONDA_BOSCH_ADDR_CHECKS_LEN (sizeof(honda_bosch_addr_checks) / sizeof(honda_bosch_addr_checks[0])) const uint16_t HONDA_PARAM_ALT_BRAKE = 1; const uint16_t HONDA_PARAM_BOSCH_LONG = 2; const uint16_t HONDA_PARAM_NIDEC_ALT = 4; const uint16_t HONDA_PARAM_RADARLESS = 8; +const uint16_t HONDA_PARAM_GAS_INTERCEPTOR = 16; enum { HONDA_BTN_NONE = 0, @@ -83,28 +98,27 @@ bool honda_fwd_brake = false; bool honda_bosch_long = false; bool honda_bosch_radarless = false; enum {HONDA_NIDEC, HONDA_BOSCH} honda_hw = HONDA_NIDEC; -addr_checks honda_rx_checks = {honda_common_addr_checks, HONDA_COMMON_ADDR_CHECKS_LEN}; int honda_get_pt_bus(void) { return ((honda_hw == HONDA_BOSCH) && !honda_bosch_radarless) ? 1 : 0; } -static uint32_t honda_get_checksum(CANPacket_t *to_push) { +static uint32_t honda_get_checksum(const CANPacket_t *to_push) { int checksum_byte = GET_LEN(to_push) - 1U; return (uint8_t)(GET_BYTE(to_push, checksum_byte)) & 0xFU; } -static uint32_t honda_compute_checksum(CANPacket_t *to_push) { +static uint32_t honda_compute_checksum(const CANPacket_t *to_push) { int len = GET_LEN(to_push); uint8_t checksum = 0U; unsigned int addr = GET_ADDR(to_push); while (addr > 0U) { - checksum += (addr & 0xFU); addr >>= 4; + checksum += (uint8_t)(addr & 0xFU); addr >>= 4; } for (int j = 0; j < len; j++) { uint8_t byte = GET_BYTE(to_push, j); - checksum += (byte & 0xFU) + (byte >> 4U); + checksum += (uint8_t)(byte & 0xFU) + (byte >> 4U); if (j == (len - 1)) { checksum -= (byte & 0xFU); // remove checksum in message } @@ -112,171 +126,154 @@ static uint32_t honda_compute_checksum(CANPacket_t *to_push) { return (uint8_t)((8U - checksum) & 0xFU); } -static uint8_t honda_get_counter(CANPacket_t *to_push) { - int counter_byte = GET_LEN(to_push) - 1U; - return ((uint8_t)(GET_BYTE(to_push, counter_byte)) >> 4U) & 0x3U; -} +static uint8_t honda_get_counter(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); -static int honda_rx_hook(CANPacket_t *to_push) { + uint8_t cnt = 0U; + if (addr == 0x201) { + // Signal: COUNTER_PEDAL + cnt = GET_BYTE(to_push, 4) & 0x0FU; + } else { + int counter_byte = GET_LEN(to_push) - 1U; + cnt = (GET_BYTE(to_push, counter_byte) >> 4U) & 0x3U; + } + return cnt; +} - bool valid = addr_safety_check(to_push, &honda_rx_checks, - honda_get_checksum, honda_compute_checksum, honda_get_counter, NULL); +static void honda_rx_hook(const CANPacket_t *to_push) { + const bool pcm_cruise = ((honda_hw == HONDA_BOSCH) && !honda_bosch_long) || \ + ((honda_hw == HONDA_NIDEC) && !enable_gas_interceptor); + int pt_bus = honda_get_pt_bus(); - if (valid) { - const bool pcm_cruise = ((honda_hw == HONDA_BOSCH) && !honda_bosch_long) || \ - ((honda_hw == HONDA_NIDEC) && !gas_interceptor_detected); - int pt_bus = honda_get_pt_bus(); + int addr = GET_ADDR(to_push); + int len = GET_LEN(to_push); + int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - int bus = GET_BUS(to_push); + // sample speed + if (addr == 0x158) { + // first 2 bytes + vehicle_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1); + } - // sample speed - if (addr == 0x158) { - // first 2 bytes - vehicle_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1); + // check ACC main state + // 0x326 for all Bosch and some Nidec, 0x1A6 for some Nidec + if ((addr == 0x326) || (addr == 0x1A6)) { + acc_main_on = GET_BIT(to_push, ((addr == 0x326) ? 28U : 47U)); + if (!acc_main_on) { + controls_allowed = false; } + } - // check ACC main state - // 0x326 for all Bosch and some Nidec, 0x1A6 for some Nidec - if ((addr == 0x326) || (addr == 0x1A6)) { - acc_main_on = GET_BIT(to_push, ((addr == 0x326) ? 28U : 47U)); - if (!acc_main_on) { - controls_allowed = false; - } + // enter controls when PCM enters cruise state + if (pcm_cruise && (addr == 0x17C)) { + const bool cruise_engaged = GET_BIT(to_push, 38U); + // engage on rising edge + if (cruise_engaged && !cruise_engaged_prev) { + controls_allowed = true; } - // enter controls when PCM enters cruise state - if (pcm_cruise && (addr == 0x17C)) { - const bool cruise_engaged = GET_BIT(to_push, 38U) != 0U; - // engage on rising edge - if (cruise_engaged && !cruise_engaged_prev) { - controls_allowed = true; - } - - // Since some Nidec cars can brake down to 0 after the PCM disengages, - // we don't disengage when the PCM does. - if (!cruise_engaged && (honda_hw != HONDA_NIDEC)) { - controls_allowed = false; - } - cruise_engaged_prev = cruise_engaged; + // Since some Nidec cars can brake down to 0 after the PCM disengages, + // we don't disengage when the PCM does. + if (!cruise_engaged && (honda_hw != HONDA_NIDEC)) { + controls_allowed = false; } + cruise_engaged_prev = cruise_engaged; + } - // state machine to enter and exit controls for button enabling - // 0x1A6 for the ILX, 0x296 for the Civic Touring - if (((addr == 0x1A6) || (addr == 0x296)) && (bus == pt_bus)) { - int button = (GET_BYTE(to_push, 0) & 0xE0U) >> 5; - - // enter controls on the falling edge of set or resume - bool set = (button != HONDA_BTN_SET) && (cruise_button_prev == HONDA_BTN_SET); - bool res = (button != HONDA_BTN_RESUME) && (cruise_button_prev == HONDA_BTN_RESUME); - if (acc_main_on && !pcm_cruise && (set || res)) { - controls_allowed = true; - } + // state machine to enter and exit controls for button enabling + // 0x1A6 for the ILX, 0x296 for the Civic Touring + if (((addr == 0x1A6) || (addr == 0x296)) && (bus == pt_bus)) { + int button = (GET_BYTE(to_push, 0) & 0xE0U) >> 5; - // exit controls once main or cancel are pressed - if ((button == HONDA_BTN_MAIN) || (button == HONDA_BTN_CANCEL)) { - controls_allowed = false; - } - cruise_button_prev = button; + // enter controls on the falling edge of set or resume + bool set = (button != HONDA_BTN_SET) && (cruise_button_prev == HONDA_BTN_SET); + bool res = (button != HONDA_BTN_RESUME) && (cruise_button_prev == HONDA_BTN_RESUME); + if (acc_main_on && !pcm_cruise && (set || res)) { + controls_allowed = true; } - // user brake signal on 0x17C reports applied brake from computer brake on accord - // and crv, which prevents the usual brake safety from working correctly. these - // cars have a signal on 0x1BE which only detects user's brake being applied so - // in these cases, this is used instead. - // most hondas: 0x17C - // accord, crv: 0x1BE - if (honda_alt_brake_msg) { - if (addr == 0x1BE) { - brake_pressed = GET_BIT(to_push, 4U) != 0U; - } - } else { - if (addr == 0x17C) { - // also if brake switch is 1 for two CAN frames, as brake pressed is delayed - const bool brake_switch = GET_BIT(to_push, 32U) != 0U; - brake_pressed = (GET_BIT(to_push, 53U) != 0U) || (brake_switch && honda_brake_switch_prev); - honda_brake_switch_prev = brake_switch; - } + // exit controls once main or cancel are pressed + if ((button == HONDA_BTN_MAIN) || (button == HONDA_BTN_CANCEL)) { + controls_allowed = false; } + cruise_button_prev = button; + } - // length check because bosch hardware also uses this id (0x201 w/ len = 8) - if ((addr == 0x201) && (len == 6)) { - gas_interceptor_detected = 1; - int gas_interceptor = HONDA_GET_INTERCEPTOR(to_push); - gas_pressed = gas_interceptor > HONDA_GAS_INTERCEPTOR_THRESHOLD; - gas_interceptor_prev = gas_interceptor; + // user brake signal on 0x17C reports applied brake from computer brake on accord + // and crv, which prevents the usual brake safety from working correctly. these + // cars have a signal on 0x1BE which only detects user's brake being applied so + // in these cases, this is used instead. + // most hondas: 0x17C + // accord, crv: 0x1BE + if (honda_alt_brake_msg) { + if (addr == 0x1BE) { + brake_pressed = GET_BIT(to_push, 4U); } + } else { + if (addr == 0x17C) { + // also if brake switch is 1 for two CAN frames, as brake pressed is delayed + const bool brake_switch = GET_BIT(to_push, 32U); + brake_pressed = (GET_BIT(to_push, 53U)) || (brake_switch && honda_brake_switch_prev); + honda_brake_switch_prev = brake_switch; + } + } - if (!gas_interceptor_detected) { - if (addr == 0x17C) { - gas_pressed = GET_BYTE(to_push, 0) != 0U; - } + // length check because bosch hardware also uses this id (0x201 w/ len = 8) + if ((addr == 0x201) && (len == 6) && enable_gas_interceptor) { + int gas_interceptor = HONDA_GET_INTERCEPTOR(to_push); + gas_pressed = gas_interceptor > HONDA_GAS_INTERCEPTOR_THRESHOLD; + gas_interceptor_prev = gas_interceptor; + } + + if (!enable_gas_interceptor) { + if (addr == 0x17C) { + gas_pressed = GET_BYTE(to_push, 0) != 0U; } + } - // disable stock Honda AEB in alternative experience - if (!(alternative_experience & ALT_EXP_DISABLE_STOCK_AEB)) { - if ((bus == 2) && (addr == 0x1FA)) { - bool honda_stock_aeb = GET_BIT(to_push, 29U) != 0U; - int honda_stock_brake = (GET_BYTE(to_push, 0) << 2) | (GET_BYTE(to_push, 1) >> 6); - - // Forward AEB when stock braking is higher than openpilot braking - // only stop forwarding when AEB event is over - if (!honda_stock_aeb) { - honda_fwd_brake = false; - } else if (honda_stock_brake >= honda_brake) { - honda_fwd_brake = true; - } else { - // Leave Honda forward brake as is - } + // disable stock Honda AEB in alternative experience + if (!(alternative_experience & ALT_EXP_DISABLE_STOCK_AEB)) { + if ((bus == 2) && (addr == 0x1FA)) { + bool honda_stock_aeb = GET_BIT(to_push, 29U); + int honda_stock_brake = (GET_BYTE(to_push, 0) << 2) | (GET_BYTE(to_push, 1) >> 6); + + // Forward AEB when stock braking is higher than openpilot braking + // only stop forwarding when AEB event is over + if (!honda_stock_aeb) { + honda_fwd_brake = false; + } else if (honda_stock_brake >= honda_brake) { + honda_fwd_brake = true; + } else { + // Leave Honda forward brake as is } } + } - int bus_rdr_car = (honda_hw == HONDA_BOSCH) ? 0 : 2; // radar bus, car side - bool stock_ecu_detected = false; + int bus_rdr_car = (honda_hw == HONDA_BOSCH) ? 0 : 2; // radar bus, car side + bool stock_ecu_detected = false; - // If steering controls messages are received on the destination bus, it's an indication - // that the relay might be malfunctioning - if ((addr == 0xE4) || (addr == 0x194)) { - if (((honda_hw != HONDA_NIDEC) && (bus == bus_rdr_car)) || ((honda_hw == HONDA_NIDEC) && (bus == 0))) { - stock_ecu_detected = true; - } - } - // If Honda Bosch longitudinal mode is selected we need to ensure the radar is turned off - // Verify this by ensuring ACC_CONTROL (0x1DF) is not received on the PT bus - if (honda_bosch_long && !honda_bosch_radarless && (bus == pt_bus) && (addr == 0x1DF)) { + // If steering controls messages are received on the destination bus, it's an indication + // that the relay might be malfunctioning + if ((addr == 0xE4) || (addr == 0x194)) { + if (((honda_hw != HONDA_NIDEC) && (bus == bus_rdr_car)) || ((honda_hw == HONDA_NIDEC) && (bus == 0))) { stock_ecu_detected = true; } - - generic_rx_checks(stock_ecu_detected); } - return valid; -} + // If Honda Bosch longitudinal mode is selected we need to ensure the radar is turned off + // Verify this by ensuring ACC_CONTROL (0x1DF) is not received on the PT bus + if (honda_bosch_long && !honda_bosch_radarless && (bus == pt_bus) && (addr == 0x1DF)) { + stock_ecu_detected = true; + } -// all commands: gas, brake and steering -// if controls_allowed and no pedals pressed -// allow all commands up to limit -// else -// block all commands that produce actuation + generic_rx_checks(stock_ecu_detected); -static int honda_tx_hook(CANPacket_t *to_send) { +} - int tx = 1; +static bool honda_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); - if ((honda_hw == HONDA_BOSCH) && honda_bosch_radarless && !honda_bosch_long) { - tx = msg_allowed(to_send, HONDA_RADARLESS_TX_MSGS, sizeof(HONDA_RADARLESS_TX_MSGS)/sizeof(HONDA_RADARLESS_TX_MSGS[0])); - } else if ((honda_hw == HONDA_BOSCH) && honda_bosch_radarless && honda_bosch_long) { - tx = msg_allowed(to_send, HONDA_RADARLESS_LONG_TX_MSGS, sizeof(HONDA_RADARLESS_LONG_TX_MSGS)/sizeof(HONDA_RADARLESS_LONG_TX_MSGS[0])); - } else if ((honda_hw == HONDA_BOSCH) && !honda_bosch_long) { - tx = msg_allowed(to_send, HONDA_BOSCH_TX_MSGS, sizeof(HONDA_BOSCH_TX_MSGS)/sizeof(HONDA_BOSCH_TX_MSGS[0])); - } else if ((honda_hw == HONDA_BOSCH) && honda_bosch_long) { - tx = msg_allowed(to_send, HONDA_BOSCH_LONG_TX_MSGS, sizeof(HONDA_BOSCH_LONG_TX_MSGS)/sizeof(HONDA_BOSCH_LONG_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, HONDA_N_TX_MSGS, sizeof(HONDA_N_TX_MSGS)/sizeof(HONDA_N_TX_MSGS[0])); - } - int bus_pt = honda_get_pt_bus(); int bus_buttons = (honda_bosch_radarless) ? 2 : bus_pt; // the camera controls ACC on radarless Bosch cars @@ -289,7 +286,7 @@ static int honda_tx_hook(CANPacket_t *to_send) { violation |= longitudinal_speed_checks(pcm_speed, HONDA_NIDEC_LONG_LIMITS); violation |= longitudinal_gas_checks(pcm_gas, HONDA_NIDEC_LONG_LIMITS); if (violation) { - tx = 0; + tx = false; } } @@ -297,10 +294,10 @@ static int honda_tx_hook(CANPacket_t *to_send) { if ((addr == 0x1FA) && (bus == bus_pt)) { honda_brake = (GET_BYTE(to_send, 0) << 2) + ((GET_BYTE(to_send, 1) >> 6) & 0x3U); if (longitudinal_brake_checks(honda_brake, HONDA_NIDEC_LONG_LIMITS)) { - tx = 0; + tx = false; } if (honda_fwd_brake) { - tx = 0; + tx = false; } } @@ -316,7 +313,7 @@ static int honda_tx_hook(CANPacket_t *to_send) { violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS); violation |= longitudinal_gas_checks(gas, HONDA_BOSCH_LONG_LIMITS); if (violation) { - tx = 0; + tx = false; } } @@ -328,7 +325,7 @@ static int honda_tx_hook(CANPacket_t *to_send) { bool violation = false; violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS); if (violation) { - tx = 0; + tx = false; } } @@ -337,7 +334,7 @@ static int honda_tx_hook(CANPacket_t *to_send) { if (!controls_allowed) { bool steer_applied = GET_BYTE(to_send, 0) | GET_BYTE(to_send, 1); if (steer_applied) { - tx = 0; + tx = false; } } } @@ -345,14 +342,14 @@ static int honda_tx_hook(CANPacket_t *to_send) { // Bosch supplemental control check if (addr == 0xE5) { if ((GET_BYTES(to_send, 0, 4) != 0x10800004U) || ((GET_BYTES(to_send, 4, 4) & 0x00FFFFFFU) != 0x0U)) { - tx = 0; + tx = false; } } // GAS: safety check (interceptor) if (addr == 0x200) { if (longitudinal_interceptor_checks(to_send)) { - tx = 0; + tx = false; } } @@ -361,39 +358,52 @@ static int honda_tx_hook(CANPacket_t *to_send) { // This avoids unintended engagements while still allowing resume spam if ((addr == 0x296) && !controls_allowed && (bus == bus_buttons)) { if (((GET_BYTE(to_send, 0) >> 5) & 0x7U) != 2U) { - tx = 0; + tx = false; } } // Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address if (addr == 0x18DAB0F1) { if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) { - tx = 0; + tx = false; } } - // 1 allows the message through return tx; } -static const addr_checks* honda_nidec_init(uint16_t param) { +static safety_config honda_nidec_init(uint16_t param) { honda_hw = HONDA_NIDEC; honda_brake = 0; + honda_brake_switch_prev = false; honda_fwd_brake = false; honda_alt_brake_msg = false; honda_bosch_long = false; honda_bosch_radarless = false; + enable_gas_interceptor = GET_FLAG(param, HONDA_PARAM_GAS_INTERCEPTOR); - if (GET_FLAG(param, HONDA_PARAM_NIDEC_ALT)) { - honda_rx_checks = (addr_checks){honda_nidec_alt_addr_checks, HONDA_NIDEC_ALT_ADDR_CHECKS_LEN}; + safety_config ret; + + bool enable_nidec_alt = GET_FLAG(param, HONDA_PARAM_NIDEC_ALT); + if (enable_nidec_alt) { + enable_gas_interceptor ? SET_RX_CHECKS(honda_nidec_alt_interceptor_rx_checks, ret) : \ + SET_RX_CHECKS(honda_nidec_alt_rx_checks, ret); + } else { + enable_gas_interceptor ? SET_RX_CHECKS(honda_common_interceptor_rx_checks, ret) : \ + SET_RX_CHECKS(honda_common_rx_checks, ret); + } + + if (enable_gas_interceptor) { + SET_TX_MSGS(HONDA_N_INTERCEPTOR_TX_MSGS, ret); } else { - honda_rx_checks = (addr_checks){honda_common_addr_checks, HONDA_COMMON_ADDR_CHECKS_LEN}; + SET_TX_MSGS(HONDA_N_TX_MSGS, ret); } - return &honda_rx_checks; + return ret; } -static const addr_checks* honda_bosch_init(uint16_t param) { +static safety_config honda_bosch_init(uint16_t param) { honda_hw = HONDA_BOSCH; + honda_brake_switch_prev = false; honda_bosch_radarless = GET_FLAG(param, HONDA_PARAM_RADARLESS); // Checking for alternate brake override from safety parameter honda_alt_brake_msg = GET_FLAG(param, HONDA_PARAM_ALT_BRAKE); @@ -403,12 +413,25 @@ static const addr_checks* honda_bosch_init(uint16_t param) { honda_bosch_long = GET_FLAG(param, HONDA_PARAM_BOSCH_LONG); #endif + safety_config ret; + if (honda_bosch_radarless && honda_alt_brake_msg) { + SET_RX_CHECKS(honda_common_alt_brake_rx_checks, ret); + } else if (honda_bosch_radarless) { + SET_RX_CHECKS(honda_common_rx_checks, ret); + } else if (honda_alt_brake_msg) { + SET_RX_CHECKS(honda_bosch_alt_brake_rx_checks, ret); + } else { + SET_RX_CHECKS(honda_bosch_rx_checks, ret); + } + if (honda_bosch_radarless) { - honda_rx_checks = (addr_checks){honda_common_addr_checks, HONDA_COMMON_ADDR_CHECKS_LEN}; + honda_bosch_long ? SET_TX_MSGS(HONDA_RADARLESS_LONG_TX_MSGS, ret) : \ + SET_TX_MSGS(HONDA_RADARLESS_TX_MSGS, ret); } else { - honda_rx_checks = (addr_checks){honda_bosch_addr_checks, HONDA_BOSCH_ADDR_CHECKS_LEN}; + honda_bosch_long ? SET_TX_MSGS(HONDA_BOSCH_LONG_TX_MSGS, ret) : \ + SET_TX_MSGS(HONDA_BOSCH_TX_MSGS, ret); } - return &honda_rx_checks; + return ret; } static int honda_nidec_fwd_hook(int bus_num, int addr) { @@ -442,8 +465,8 @@ static int honda_bosch_fwd_hook(int bus_num, int addr) { bus_fwd = 2; } if (bus_num == 2) { - int is_lkas_msg = (addr == 0xE4) || (addr == 0xE5) || (addr == 0x33D) || (addr == 0x33DA) || (addr == 0x33DB); - int is_acc_msg = ((addr == 0x1C8) || (addr == 0x30C)) && honda_bosch_radarless && honda_bosch_long; + bool is_lkas_msg = (addr == 0xE4) || (addr == 0xE5) || (addr == 0x33D) || (addr == 0x33DA) || (addr == 0x33DB); + bool is_acc_msg = ((addr == 0x1C8) || (addr == 0x30C)) && honda_bosch_radarless && honda_bosch_long; bool block_msg = is_lkas_msg || is_acc_msg; if (!block_msg) { bus_fwd = 0; @@ -457,14 +480,18 @@ const safety_hooks honda_nidec_hooks = { .init = honda_nidec_init, .rx = honda_rx_hook, .tx = honda_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = honda_nidec_fwd_hook, + .get_counter = honda_get_counter, + .get_checksum = honda_get_checksum, + .compute_checksum = honda_compute_checksum, }; const safety_hooks honda_bosch_hooks = { .init = honda_bosch_init, .rx = honda_rx_hook, .tx = honda_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = honda_bosch_fwd_hook, + .get_counter = honda_get_counter, + .get_checksum = honda_get_checksum, + .compute_checksum = honda_compute_checksum, }; diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h index 29a42c7a01..5a324bff29 100644 --- a/panda/board/safety/safety_hyundai.h +++ b/panda/board/safety/safety_hyundai.h @@ -51,42 +51,41 @@ const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = { {0x485, 0, 4}, // LFAHDA_MFC Bus 0 }; -#define HYUNDAI_COMMON_ADDR_CHECKS(legacy) \ - {.msg = {{0x260, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, \ - {0x371, 0, 8, .expected_timestep = 10000U}, { 0 }}}, \ - {.msg = {{0x386, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, \ - {.msg = {{0x394, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 7U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, \ +#define HYUNDAI_COMMON_RX_CHECKS(legacy) \ + {.msg = {{0x260, 0, 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, \ + {0x371, 0, 8, .frequency = 100U}, { 0 }}}, \ + {.msg = {{0x386, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 15U, .frequency = 100U}, { 0 }, { 0 }}}, \ + {.msg = {{0x394, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 7U, .frequency = 100U}, { 0 }, { 0 }}}, \ #define HYUNDAI_SCC12_ADDR_CHECK(scc_bus) \ - {.msg = {{0x421, (scc_bus), 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ + {.msg = {{0x421, (scc_bus), 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ -AddrCheckStruct hyundai_addr_checks[] = { - HYUNDAI_COMMON_ADDR_CHECKS(false) +RxCheck hyundai_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(false) HYUNDAI_SCC12_ADDR_CHECK(0) }; -AddrCheckStruct hyundai_cam_scc_addr_checks[] = { - HYUNDAI_COMMON_ADDR_CHECKS(false) +RxCheck hyundai_cam_scc_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(false) HYUNDAI_SCC12_ADDR_CHECK(2) }; -AddrCheckStruct hyundai_long_addr_checks[] = { - HYUNDAI_COMMON_ADDR_CHECKS(false) +RxCheck hyundai_long_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(false) // Use CLU11 (buttons) to manage controls allowed instead of SCC cruise state - {.msg = {{0x4F1, 0, 4, .check_checksum = false, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{0x4F1, 0, 4, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, }; // older hyundai models have less checks due to missing counters and checksums -AddrCheckStruct hyundai_legacy_addr_checks[] = { - HYUNDAI_COMMON_ADDR_CHECKS(true) +RxCheck hyundai_legacy_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(true) HYUNDAI_SCC12_ADDR_CHECK(0) }; bool hyundai_legacy = false; -addr_checks hyundai_rx_checks = SET_ADDR_CHECKS(hyundai_addr_checks); -static uint8_t hyundai_get_counter(CANPacket_t *to_push) { +static uint8_t hyundai_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t cnt = 0; @@ -105,7 +104,7 @@ static uint8_t hyundai_get_counter(CANPacket_t *to_push) { return cnt; } -static uint32_t hyundai_get_checksum(CANPacket_t *to_push) { +static uint32_t hyundai_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -122,7 +121,7 @@ static uint32_t hyundai_get_checksum(CANPacket_t *to_push) { return chksum; } -static uint32_t hyundai_compute_checksum(CANPacket_t *to_push) { +static uint32_t hyundai_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t chksum = 0; @@ -158,23 +157,18 @@ static uint32_t hyundai_compute_checksum(CANPacket_t *to_push) { return chksum; } -static int hyundai_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &hyundai_rx_checks, - hyundai_get_checksum, hyundai_compute_checksum, - hyundai_get_counter, NULL); - +static void hyundai_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); // SCC12 is on bus 2 for camera-based SCC cars, bus 0 on all others - if (valid && (addr == 0x421) && (((bus == 0) && !hyundai_camera_scc) || ((bus == 2) && hyundai_camera_scc))) { + if ((addr == 0x421) && (((bus == 0) && !hyundai_camera_scc) || ((bus == 2) && hyundai_camera_scc))) { // 2 bits: 13-14 int cruise_engaged = (GET_BYTES(to_push, 0, 4) >> 13) & 0x3U; hyundai_common_cruise_state_check(cruise_engaged); } - if (valid && (bus == 0)) { + if (bus == 0) { if (addr == 0x251) { int torque_driver_new = (GET_BYTES(to_push, 0, 2) & 0x7ffU) - 1024U; // update array of samples @@ -184,7 +178,7 @@ static int hyundai_rx_hook(CANPacket_t *to_push) { // ACC steering wheel buttons if (addr == 0x4F1) { int cruise_button = GET_BYTE(to_push, 0) & 0x7U; - int main_button = GET_BIT(to_push, 3U); + bool main_button = GET_BIT(to_push, 3U); hyundai_common_cruise_buttons_check(cruise_button, main_button); } @@ -206,7 +200,7 @@ static int hyundai_rx_hook(CANPacket_t *to_push) { } if (addr == 0x394) { - brake_pressed = ((GET_BYTE(to_push, 5) >> 5U) & 0x2U) == 0x2U; + brake_pressed = ((GET_BYTE(to_push, 5) >> 5U) & 0x3U) == 0x2U; } bool stock_ecu_detected = (addr == 0x340); @@ -218,30 +212,20 @@ static int hyundai_rx_hook(CANPacket_t *to_push) { } generic_rx_checks(stock_ecu_detected); } - return valid; } -static int hyundai_tx_hook(CANPacket_t *to_send) { - - int tx = 1; +static bool hyundai_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); - if (hyundai_longitudinal) { - tx = msg_allowed(to_send, HYUNDAI_LONG_TX_MSGS, sizeof(HYUNDAI_LONG_TX_MSGS)/sizeof(HYUNDAI_LONG_TX_MSGS[0])); - } else if (hyundai_camera_scc) { - tx = msg_allowed(to_send, HYUNDAI_CAMERA_SCC_TX_MSGS, sizeof(HYUNDAI_CAMERA_SCC_TX_MSGS)/sizeof(HYUNDAI_CAMERA_SCC_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, HYUNDAI_TX_MSGS, sizeof(HYUNDAI_TX_MSGS)/sizeof(HYUNDAI_TX_MSGS[0])); - } - // FCA11: Block any potential actuation if (addr == 0x38D) { int CR_VSM_DecCmd = GET_BYTE(to_send, 1); - int FCA_CmdAct = GET_BIT(to_send, 20U); - int CF_VSM_DecCmdAct = GET_BIT(to_send, 31U); + bool FCA_CmdAct = GET_BIT(to_send, 20U); + bool CF_VSM_DecCmdAct = GET_BIT(to_send, 31U); - if ((CR_VSM_DecCmd != 0) || (FCA_CmdAct != 0) || (CF_VSM_DecCmdAct != 0)) { - tx = 0; + if ((CR_VSM_DecCmd != 0) || FCA_CmdAct || CF_VSM_DecCmdAct) { + tx = false; } } @@ -251,35 +235,35 @@ static int hyundai_tx_hook(CANPacket_t *to_send) { int desired_accel_val = ((GET_BYTE(to_send, 5) << 3) | (GET_BYTE(to_send, 4) >> 5)) - 1023U; int aeb_decel_cmd = GET_BYTE(to_send, 2); - int aeb_req = GET_BIT(to_send, 54U); + bool aeb_req = GET_BIT(to_send, 54U); bool violation = false; violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS); violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS); violation |= (aeb_decel_cmd != 0); - violation |= (aeb_req != 0); + violation |= aeb_req; if (violation) { - tx = 0; + tx = false; } } // LKA STEER: safety check if (addr == 0x340) { int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 16) & 0x7ffU) - 1024U; - bool steer_req = GET_BIT(to_send, 27U) != 0U; + bool steer_req = GET_BIT(to_send, 27U); const SteeringLimits limits = hyundai_alt_limits ? HYUNDAI_STEERING_LIMITS_ALT : HYUNDAI_STEERING_LIMITS; if (steer_torque_cmd_checks(desired_torque, steer_req, limits)) { - tx = 0; + tx = false; } } // UDS: Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address if (addr == 0x7D0) { if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) { - tx = 0; + tx = false; } } @@ -290,7 +274,7 @@ static int hyundai_tx_hook(CANPacket_t *to_send) { bool allowed_resume = (button == 1) && controls_allowed; bool allowed_cancel = (button == 4) && cruise_engaged_prev; if (!(allowed_resume || allowed_cancel)) { - tx = 0; + tx = false; } } @@ -312,7 +296,7 @@ static int hyundai_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* hyundai_init(uint16_t param) { +static safety_config hyundai_init(uint16_t param) { hyundai_common_init(param); hyundai_legacy = false; @@ -320,38 +304,41 @@ static const addr_checks* hyundai_init(uint16_t param) { hyundai_longitudinal = false; } + safety_config ret; if (hyundai_longitudinal) { - hyundai_rx_checks = SET_ADDR_CHECKS(hyundai_long_addr_checks); + ret = BUILD_SAFETY_CFG(hyundai_long_rx_checks, HYUNDAI_LONG_TX_MSGS); } else if (hyundai_camera_scc) { - hyundai_rx_checks = SET_ADDR_CHECKS(hyundai_cam_scc_addr_checks); + ret = BUILD_SAFETY_CFG(hyundai_cam_scc_rx_checks, HYUNDAI_CAMERA_SCC_TX_MSGS); } else { - hyundai_rx_checks = SET_ADDR_CHECKS(hyundai_addr_checks); + ret = BUILD_SAFETY_CFG(hyundai_rx_checks, HYUNDAI_TX_MSGS); } - return &hyundai_rx_checks; + return ret; } -static const addr_checks* hyundai_legacy_init(uint16_t param) { +static safety_config hyundai_legacy_init(uint16_t param) { hyundai_common_init(param); hyundai_legacy = true; hyundai_longitudinal = false; hyundai_camera_scc = false; - - hyundai_rx_checks = SET_ADDR_CHECKS(hyundai_legacy_addr_checks); - return &hyundai_rx_checks; + return BUILD_SAFETY_CFG(hyundai_legacy_rx_checks, HYUNDAI_TX_MSGS); } const safety_hooks hyundai_hooks = { .init = hyundai_init, .rx = hyundai_rx_hook, .tx = hyundai_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = hyundai_fwd_hook, + .get_counter = hyundai_get_counter, + .get_checksum = hyundai_get_checksum, + .compute_checksum = hyundai_compute_checksum, }; const safety_hooks hyundai_legacy_hooks = { .init = hyundai_legacy_init, .rx = hyundai_rx_hook, .tx = hyundai_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = hyundai_fwd_hook, + .get_counter = hyundai_get_counter, + .get_checksum = hyundai_get_checksum, + .compute_checksum = hyundai_compute_checksum, }; diff --git a/panda/board/safety/safety_hyundai_canfd.h b/panda/board/safety/safety_hyundai_canfd.h index f0af9060eb..fb6ccf55a0 100644 --- a/panda/board/safety/safety_hyundai_canfd.h +++ b/panda/board/safety/safety_hyundai_canfd.h @@ -56,57 +56,57 @@ const CanMsg HYUNDAI_CANFD_HDA1_TX_MSGS[] = { // *** Addresses checked in rx hook *** // EV, ICE, HYBRID: ACCELERATOR (0x35), ACCELERATOR_BRAKE_ALT (0x100), ACCELERATOR_ALT (0x105) -#define HYUNDAI_CANFD_COMMON_ADDR_CHECKS(pt_bus) \ - {.msg = {{0x35, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 10000U}, \ - {0x100, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 10000U}, \ - {0x105, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 10000U}}}, \ - {.msg = {{0x175, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ - {.msg = {{0xa0, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 10000U}, { 0 }, { 0 }}}, \ - {.msg = {{0xea, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 10000U}, { 0 }, { 0 }}}, \ +#define HYUNDAI_CANFD_COMMON_RX_CHECKS(pt_bus) \ + {.msg = {{0x35, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, \ + {0x100, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, \ + {0x105, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}}}, \ + {.msg = {{0x175, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ + {.msg = {{0xa0, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, { 0 }, { 0 }}}, \ + {.msg = {{0xea, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, { 0 }, { 0 }}}, \ #define HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(pt_bus) \ - {.msg = {{0x1cf, (pt_bus), 8, .check_checksum = false, .max_counter = 0xfU, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ + {.msg = {{0x1cf, (pt_bus), 8, .check_checksum = false, .max_counter = 0xfU, .frequency = 50U}, { 0 }, { 0 }}}, \ #define HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(pt_bus) \ - {.msg = {{0x1aa, (pt_bus), 16, .check_checksum = false, .max_counter = 0xffU, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ + {.msg = {{0x1aa, (pt_bus), 16, .check_checksum = false, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ // SCC_CONTROL (from ADAS unit or camera) #define HYUNDAI_CANFD_SCC_ADDR_CHECK(scc_bus) \ - {.msg = {{0x1a0, (scc_bus), 32, .check_checksum = true, .max_counter = 0xffU, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ + {.msg = {{0x1a0, (scc_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ // *** Non-HDA2 checks *** // Camera sends SCC messages on HDA1. // Both button messages exist on some platforms, so we ensure we track the correct one using flag -AddrCheckStruct hyundai_canfd_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(0) +RxCheck hyundai_canfd_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) HYUNDAI_CANFD_SCC_ADDR_CHECK(2) }; -AddrCheckStruct hyundai_canfd_alt_buttons_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(0) +RxCheck hyundai_canfd_alt_buttons_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) HYUNDAI_CANFD_SCC_ADDR_CHECK(2) }; // Longitudinal checks for HDA1 -AddrCheckStruct hyundai_canfd_long_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(0) +RxCheck hyundai_canfd_long_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) }; -AddrCheckStruct hyundai_canfd_long_alt_buttons_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(0) +RxCheck hyundai_canfd_long_alt_buttons_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) }; // Radar sends SCC messages on these cars instead of camera -AddrCheckStruct hyundai_canfd_radar_scc_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(0) +RxCheck hyundai_canfd_radar_scc_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) HYUNDAI_CANFD_SCC_ADDR_CHECK(0) }; -AddrCheckStruct hyundai_canfd_radar_scc_alt_buttons_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(0) +RxCheck hyundai_canfd_radar_scc_alt_buttons_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) HYUNDAI_CANFD_SCC_ADDR_CHECK(0) }; @@ -115,17 +115,16 @@ AddrCheckStruct hyundai_canfd_radar_scc_alt_buttons_addr_checks[] = { // *** HDA2 checks *** // E-CAN is on bus 1, ADAS unit sends SCC messages on HDA2. // Does not use the alt buttons message -AddrCheckStruct hyundai_canfd_hda2_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(1) +RxCheck hyundai_canfd_hda2_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(1) HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) HYUNDAI_CANFD_SCC_ADDR_CHECK(1) }; -AddrCheckStruct hyundai_canfd_hda2_long_addr_checks[] = { - HYUNDAI_CANFD_COMMON_ADDR_CHECKS(1) +RxCheck hyundai_canfd_hda2_long_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(1) HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) }; -addr_checks hyundai_canfd_rx_checks = SET_ADDR_CHECKS(hyundai_canfd_addr_checks); const int HYUNDAI_PARAM_CANFD_ALT_BUTTONS = 32; @@ -138,7 +137,7 @@ int hyundai_canfd_hda2_get_lkas_addr(void) { return hyundai_canfd_hda2_alt_steering ? 0x110 : 0x50; } -static uint8_t hyundai_canfd_get_counter(CANPacket_t *to_push) { +static uint8_t hyundai_canfd_get_counter(const CANPacket_t *to_push) { uint8_t ret = 0; if (GET_LEN(to_push) == 8U) { ret = GET_BYTE(to_push, 1) >> 4; @@ -148,23 +147,19 @@ static uint8_t hyundai_canfd_get_counter(CANPacket_t *to_push) { return ret; } -static uint32_t hyundai_canfd_get_checksum(CANPacket_t *to_push) { +static uint32_t hyundai_canfd_get_checksum(const CANPacket_t *to_push) { uint32_t chksum = GET_BYTE(to_push, 0) | (GET_BYTE(to_push, 1) << 8); return chksum; } -static int hyundai_canfd_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &hyundai_canfd_rx_checks, - hyundai_canfd_get_checksum, hyundai_common_canfd_compute_checksum, hyundai_canfd_get_counter, NULL); - +static void hyundai_canfd_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); int addr = GET_ADDR(to_push); const int pt_bus = hyundai_canfd_hda2 ? 1 : 0; const int scc_bus = hyundai_camera_scc ? 2 : pt_bus; - if (valid && (bus == pt_bus)) { + if (bus == pt_bus) { // driver torque if (addr == 0xea) { int torque_driver_new = ((GET_BYTE(to_push, 11) & 0x1fU) << 8U) | GET_BYTE(to_push, 10); @@ -175,7 +170,7 @@ static int hyundai_canfd_rx_hook(CANPacket_t *to_push) { // cruise buttons const int button_addr = hyundai_canfd_alt_buttons ? 0x1aa : 0x1cf; if (addr == button_addr) { - int main_button = 0; + bool main_button = false; int cruise_button = 0; if (addr == 0x1cf) { cruise_button = GET_BYTE(to_push, 2) & 0x7U; @@ -191,15 +186,15 @@ static int hyundai_canfd_rx_hook(CANPacket_t *to_push) { if ((addr == 0x35) && hyundai_ev_gas_signal) { gas_pressed = GET_BYTE(to_push, 5) != 0U; } else if ((addr == 0x105) && hyundai_hybrid_gas_signal) { - gas_pressed = (GET_BIT(to_push, 103U) != 0U) || (GET_BYTE(to_push, 13) != 0U) || (GET_BIT(to_push, 112U) != 0U); + gas_pressed = GET_BIT(to_push, 103U) || (GET_BYTE(to_push, 13) != 0U) || GET_BIT(to_push, 112U); } else if ((addr == 0x100) && !hyundai_ev_gas_signal && !hyundai_hybrid_gas_signal) { - gas_pressed = GET_BIT(to_push, 176U) != 0U; + gas_pressed = GET_BIT(to_push, 176U); } else { } // brake press if (addr == 0x175) { - brake_pressed = GET_BIT(to_push, 81U) != 0U; + brake_pressed = GET_BIT(to_push, 81U); } // vehicle moving @@ -210,7 +205,7 @@ static int hyundai_canfd_rx_hook(CANPacket_t *to_push) { } } - if (valid && (bus == scc_bus)) { + if (bus == scc_bus) { // cruise state if ((addr == 0x1a0) && !hyundai_longitudinal) { // 1=enabled, 2=driver override @@ -230,34 +225,20 @@ static int hyundai_canfd_rx_hook(CANPacket_t *to_push) { } generic_rx_checks(stock_ecu_detected); - return valid; } -static int hyundai_canfd_tx_hook(CANPacket_t *to_send) { - - int tx = 0; +static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); - if (hyundai_canfd_hda2 && !hyundai_longitudinal) { - if (hyundai_canfd_hda2_alt_steering) { - tx = msg_allowed(to_send, HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS, sizeof(HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS)/sizeof(HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, HYUNDAI_CANFD_HDA2_TX_MSGS, sizeof(HYUNDAI_CANFD_HDA2_TX_MSGS)/sizeof(HYUNDAI_CANFD_HDA2_TX_MSGS[0])); - } - } else if (hyundai_canfd_hda2 && hyundai_longitudinal) { - tx = msg_allowed(to_send, HYUNDAI_CANFD_HDA2_LONG_TX_MSGS, sizeof(HYUNDAI_CANFD_HDA2_LONG_TX_MSGS)/sizeof(HYUNDAI_CANFD_HDA2_LONG_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, HYUNDAI_CANFD_HDA1_TX_MSGS, sizeof(HYUNDAI_CANFD_HDA1_TX_MSGS)/sizeof(HYUNDAI_CANFD_HDA1_TX_MSGS[0])); - } - // steering const int steer_addr = (hyundai_canfd_hda2 && !hyundai_longitudinal) ? hyundai_canfd_hda2_get_lkas_addr() : 0x12a; if (addr == steer_addr) { int desired_torque = (((GET_BYTE(to_send, 6) & 0xFU) << 7U) | (GET_BYTE(to_send, 5) >> 1U)) - 1024U; - bool steer_req = GET_BIT(to_send, 52U) != 0U; + bool steer_req = GET_BIT(to_send, 52U); if (steer_torque_cmd_checks(desired_torque, steer_req, HYUNDAI_CANFD_STEERING_LIMITS)) { - tx = 0; + tx = false; } } @@ -269,14 +250,14 @@ static int hyundai_canfd_tx_hook(CANPacket_t *to_send) { bool allowed = (is_cancel && cruise_engaged_prev) || (is_resume && controls_allowed); if (!allowed) { - tx = 0; + tx = false; } } // UDS: only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address if ((addr == 0x730) && hyundai_canfd_hda2) { if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) { - tx = 0; + tx = false; } } @@ -298,7 +279,7 @@ static int hyundai_canfd_tx_hook(CANPacket_t *to_send) { } if (violation) { - tx = 0; + tx = false; } } @@ -332,41 +313,48 @@ static int hyundai_canfd_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* hyundai_canfd_init(uint16_t param) { +static safety_config hyundai_canfd_init(uint16_t param) { hyundai_common_init(param); gen_crc_lookup_table_16(0x1021, hyundai_canfd_crc_lut); hyundai_canfd_alt_buttons = GET_FLAG(param, HYUNDAI_PARAM_CANFD_ALT_BUTTONS); hyundai_canfd_hda2_alt_steering = GET_FLAG(param, HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING); - // no long for ICE yet - if (!hyundai_ev_gas_signal && !hyundai_hybrid_gas_signal) { + // no long for radar-SCC HDA1 yet + if (!hyundai_canfd_hda2 && !hyundai_camera_scc) { hyundai_longitudinal = false; } + safety_config ret; if (hyundai_longitudinal) { if (hyundai_canfd_hda2) { - hyundai_canfd_rx_checks = SET_ADDR_CHECKS(hyundai_canfd_hda2_long_addr_checks); + ret = BUILD_SAFETY_CFG(hyundai_canfd_hda2_long_rx_checks, HYUNDAI_CANFD_HDA2_LONG_TX_MSGS); } else { - hyundai_canfd_rx_checks = hyundai_canfd_alt_buttons ? SET_ADDR_CHECKS(hyundai_canfd_long_alt_buttons_addr_checks) : SET_ADDR_CHECKS(hyundai_canfd_long_addr_checks); + ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_long_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \ + BUILD_SAFETY_CFG(hyundai_canfd_long_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS); } } else { if (hyundai_canfd_hda2) { - hyundai_canfd_rx_checks = SET_ADDR_CHECKS(hyundai_canfd_hda2_addr_checks); + ret = hyundai_canfd_hda2_alt_steering ? BUILD_SAFETY_CFG(hyundai_canfd_hda2_rx_checks, HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS) : \ + BUILD_SAFETY_CFG(hyundai_canfd_hda2_rx_checks, HYUNDAI_CANFD_HDA2_TX_MSGS); } else if (!hyundai_camera_scc) { - hyundai_canfd_rx_checks = hyundai_canfd_alt_buttons ? SET_ADDR_CHECKS(hyundai_canfd_radar_scc_alt_buttons_addr_checks) : SET_ADDR_CHECKS(hyundai_canfd_radar_scc_addr_checks); + ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_radar_scc_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \ + BUILD_SAFETY_CFG(hyundai_canfd_radar_scc_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS); } else { - hyundai_canfd_rx_checks = hyundai_canfd_alt_buttons ? SET_ADDR_CHECKS(hyundai_canfd_alt_buttons_addr_checks) : SET_ADDR_CHECKS(hyundai_canfd_addr_checks); + ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \ + BUILD_SAFETY_CFG(hyundai_canfd_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS); } } - return &hyundai_canfd_rx_checks; + return ret; } const safety_hooks hyundai_canfd_hooks = { .init = hyundai_canfd_init, .rx = hyundai_canfd_rx_hook, .tx = hyundai_canfd_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = hyundai_canfd_fwd_hook, + .get_counter = hyundai_canfd_get_counter, + .get_checksum = hyundai_canfd_get_checksum, + .compute_checksum = hyundai_common_canfd_compute_checksum, }; diff --git a/panda/board/safety/safety_hyundai_common.h b/panda/board/safety/safety_hyundai_common.h index 0b9116d147..54ea0f024a 100644 --- a/panda/board/safety/safety_hyundai_common.h +++ b/panda/board/safety/safety_hyundai_common.h @@ -45,7 +45,7 @@ void hyundai_common_init(uint16_t param) { #endif } -void hyundai_common_cruise_state_check(const int cruise_engaged) { +void hyundai_common_cruise_state_check(const bool cruise_engaged) { // some newer HKG models can re-enable after spamming cancel button, // so keep track of user button presses to deny engagement if no interaction @@ -62,9 +62,8 @@ void hyundai_common_cruise_state_check(const int cruise_engaged) { } } -void hyundai_common_cruise_buttons_check(const int cruise_button, const int main_button) { - if ((cruise_button == HYUNDAI_BTN_RESUME) || (cruise_button == HYUNDAI_BTN_SET) || (cruise_button == HYUNDAI_BTN_CANCEL) || - (main_button != 0)) { +void hyundai_common_cruise_buttons_check(const int cruise_button, const bool main_button) { + if ((cruise_button == HYUNDAI_BTN_RESUME) || (cruise_button == HYUNDAI_BTN_SET) || (cruise_button == HYUNDAI_BTN_CANCEL) || main_button) { hyundai_last_button_interaction = 0U; } else { hyundai_last_button_interaction = MIN(hyundai_last_button_interaction + 1U, HYUNDAI_PREV_BUTTON_SAMPLES); @@ -87,7 +86,7 @@ void hyundai_common_cruise_buttons_check(const int cruise_button, const int main } } -uint32_t hyundai_common_canfd_compute_checksum(CANPacket_t *to_push) { +uint32_t hyundai_common_canfd_compute_checksum(const CANPacket_t *to_push) { int len = GET_LEN(to_push); uint32_t address = GET_ADDR(to_push); diff --git a/panda/board/safety/safety_mazda.h b/panda/board/safety/safety_mazda.h index e17f1ff4b3..7c6d8be9c7 100644 --- a/panda/board/safety/safety_mazda.h +++ b/panda/board/safety/safety_mazda.h @@ -25,20 +25,17 @@ const SteeringLimits MAZDA_STEERING_LIMITS = { const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}, {MAZDA_LKAS_HUD, 0, 8}}; -AddrCheckStruct mazda_addr_checks[] = { - {.msg = {{MAZDA_CRZ_CTRL, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_CRZ_BTNS, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_STEER_TORQUE, 0, 8, .expected_timestep = 12000U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_ENGINE_DATA, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_PEDALS, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, +RxCheck mazda_rx_checks[] = { + {.msg = {{MAZDA_CRZ_CTRL, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_CRZ_BTNS, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_STEER_TORQUE, 0, 8, .frequency = 83U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_ENGINE_DATA, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MAZDA_PEDALS, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, }; -#define MAZDA_ADDR_CHECKS_LEN (sizeof(mazda_addr_checks) / sizeof(mazda_addr_checks[0])) -addr_checks mazda_rx_checks = {mazda_addr_checks, MAZDA_ADDR_CHECKS_LEN}; // track msgs coming from OP so that we know what CAM msgs to drop and what to forward -static int mazda_rx_hook(CANPacket_t *to_push) { - bool valid = addr_safety_check(to_push, &mazda_rx_checks, NULL, NULL, NULL, NULL); - if (valid && ((int)GET_BUS(to_push) == MAZDA_MAIN)) { +static void mazda_rx_hook(const CANPacket_t *to_push) { + if ((int)GET_BUS(to_push) == MAZDA_MAIN) { int addr = GET_ADDR(to_push); if (addr == MAZDA_ENGINE_DATA) { @@ -69,19 +66,13 @@ static int mazda_rx_hook(CANPacket_t *to_push) { generic_rx_checks((addr == MAZDA_LKAS)); } - return valid; } -static int mazda_tx_hook(CANPacket_t *to_send) { - - int tx = 1; +static bool mazda_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); - if (!msg_allowed(to_send, MAZDA_TX_MSGS, sizeof(MAZDA_TX_MSGS)/sizeof(MAZDA_TX_MSGS[0]))) { - tx = 0; - } - // Check if msg is sent on the main BUS if (bus == MAZDA_MAIN) { @@ -90,7 +81,7 @@ static int mazda_tx_hook(CANPacket_t *to_send) { int desired_torque = (((GET_BYTE(to_send, 0) & 0x0FU) << 8) | GET_BYTE(to_send, 1)) - 2048U; if (steer_torque_cmd_checks(desired_torque, -1, MAZDA_STEERING_LIMITS)) { - tx = 0; + tx = false; } } @@ -100,7 +91,7 @@ static int mazda_tx_hook(CANPacket_t *to_send) { // only allow cancel while contrls not allowed bool cancel_cmd = (GET_BYTE(to_send, 0) == 0x1U); if (!controls_allowed && !cancel_cmd) { - tx = 0; + tx = false; } } } @@ -125,15 +116,14 @@ static int mazda_fwd_hook(int bus, int addr) { return bus_fwd; } -static const addr_checks* mazda_init(uint16_t param) { +static safety_config mazda_init(uint16_t param) { UNUSED(param); - return &mazda_rx_checks; + return BUILD_SAFETY_CFG(mazda_rx_checks, MAZDA_TX_MSGS); } const safety_hooks mazda_hooks = { .init = mazda_init, .rx = mazda_rx_hook, .tx = mazda_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = mazda_fwd_hook, }; diff --git a/panda/board/safety/safety_nissan.h b/panda/board/safety/safety_nissan.h index ed925e7e83..c2406260fe 100644 --- a/panda/board/safety/safety_nissan.h +++ b/panda/board/safety/safety_nissan.h @@ -20,67 +20,60 @@ const CanMsg NISSAN_TX_MSGS[] = { }; // Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model. -AddrCheckStruct nissan_addr_checks[] = { - {.msg = {{0x2, 0, 5, .expected_timestep = 10000U}, - {0x2, 1, 5, .expected_timestep = 10000U}, { 0 }}}, // STEER_ANGLE_SENSOR (100Hz) - {.msg = {{0x285, 0, 8, .expected_timestep = 20000U}, - {0x285, 1, 8, .expected_timestep = 20000U}, { 0 }}}, // WHEEL_SPEEDS_REAR (50Hz) - {.msg = {{0x30f, 2, 3, .expected_timestep = 100000U}, - {0x30f, 1, 3, .expected_timestep = 100000U}, { 0 }}}, // CRUISE_STATE (10Hz) - {.msg = {{0x15c, 0, 8, .expected_timestep = 20000U}, - {0x15c, 1, 8, .expected_timestep = 20000U}, - {0x239, 0, 8, .expected_timestep = 20000U}}}, // GAS_PEDAL (100Hz / 50Hz) - {.msg = {{0x454, 0, 8, .expected_timestep = 100000U}, - {0x454, 1, 8, .expected_timestep = 100000U}, - {0x1cc, 0, 4, .expected_timestep = 10000U}}}, // DOORS_LIGHTS (10Hz) / BRAKE (100Hz) +RxCheck nissan_rx_checks[] = { + {.msg = {{0x2, 0, 5, .frequency = 100U}, + {0x2, 1, 5, .frequency = 100U}, { 0 }}}, // STEER_ANGLE_SENSOR + {.msg = {{0x285, 0, 8, .frequency = 50U}, + {0x285, 1, 8, .frequency = 50U}, { 0 }}}, // WHEEL_SPEEDS_REAR + {.msg = {{0x30f, 2, 3, .frequency = 10U}, + {0x30f, 1, 3, .frequency = 10U}, { 0 }}}, // CRUISE_STATE + {.msg = {{0x15c, 0, 8, .frequency = 50U}, + {0x15c, 1, 8, .frequency = 50U}, + {0x239, 0, 8, .frequency = 50U}}}, // GAS_PEDAL + {.msg = {{0x454, 0, 8, .frequency = 10U}, + {0x454, 1, 8, .frequency = 10U}, + {0x1cc, 0, 4, .frequency = 100U}}}, // DOORS_LIGHTS / BRAKE }; -#define NISSAN_ADDR_CHECK_LEN (sizeof(nissan_addr_checks) / sizeof(nissan_addr_checks[0])) -addr_checks nissan_rx_checks = {nissan_addr_checks, NISSAN_ADDR_CHECK_LEN}; // EPS Location. false = V-CAN, true = C-CAN const int NISSAN_PARAM_ALT_EPS_BUS = 1; bool nissan_alt_eps = false; -static int nissan_rx_hook(CANPacket_t *to_push) { +static void nissan_rx_hook(const CANPacket_t *to_push) { + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); - bool valid = addr_safety_check(to_push, &nissan_rx_checks, NULL, NULL, NULL, NULL); + if (bus == (nissan_alt_eps ? 1 : 0)) { + if (addr == 0x2) { + // Current steering angle + // Factor -0.1, little endian + int angle_meas_new = (GET_BYTES(to_push, 0, 4) & 0xFFFFU); + // Multiply by -10 to match scale of LKAS angle + angle_meas_new = to_signed(angle_meas_new, 16) * -10; - if (valid) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - if (bus == (nissan_alt_eps ? 1 : 0)) { - if (addr == 0x2) { - // Current steering angle - // Factor -0.1, little endian - int angle_meas_new = (GET_BYTES(to_push, 0, 4) & 0xFFFFU); - // Multiply by -10 to match scale of LKAS angle - angle_meas_new = to_signed(angle_meas_new, 16) * -10; - - // update array of samples - update_sample(&angle_meas, angle_meas_new); - } + // update array of samples + update_sample(&angle_meas, angle_meas_new); + } - if (addr == 0x285) { - // Get current speed and standstill - uint16_t right_rear = (GET_BYTE(to_push, 0) << 8) | (GET_BYTE(to_push, 1)); - uint16_t left_rear = (GET_BYTE(to_push, 2) << 8) | (GET_BYTE(to_push, 3)); - vehicle_moving = (right_rear | left_rear) != 0U; - update_sample(&vehicle_speed, ROUND((right_rear + left_rear) / 2.0 * 0.005 / 3.6 * VEHICLE_SPEED_FACTOR)); - } + if (addr == 0x285) { + // Get current speed and standstill + uint16_t right_rear = (GET_BYTE(to_push, 0) << 8) | (GET_BYTE(to_push, 1)); + uint16_t left_rear = (GET_BYTE(to_push, 2) << 8) | (GET_BYTE(to_push, 3)); + vehicle_moving = (right_rear | left_rear) != 0U; + UPDATE_VEHICLE_SPEED((right_rear + left_rear) / 2.0 * 0.005 / 3.6); + } - // X-Trail 0x15c, Leaf 0x239 - if ((addr == 0x15c) || (addr == 0x239)) { - if (addr == 0x15c){ - gas_pressed = ((GET_BYTE(to_push, 5) << 2) | ((GET_BYTE(to_push, 6) >> 6) & 0x3U)) > 3U; - } else { - gas_pressed = GET_BYTE(to_push, 0) > 3U; - } + // X-Trail 0x15c, Leaf 0x239 + if ((addr == 0x15c) || (addr == 0x239)) { + if (addr == 0x15c){ + gas_pressed = ((GET_BYTE(to_push, 5) << 2) | ((GET_BYTE(to_push, 6) >> 6) & 0x3U)) > 3U; + } else { + gas_pressed = GET_BYTE(to_push, 0) > 3U; } } - // X-trail 0x454, Leaf 0x239 + // X-trail 0x454, Leaf 0x239 if ((addr == 0x454) || (addr == 0x239)) { if (addr == 0x454){ brake_pressed = (GET_BYTE(to_push, 2) & 0x80U) != 0U; @@ -88,36 +81,30 @@ static int nissan_rx_hook(CANPacket_t *to_push) { brake_pressed = ((GET_BYTE(to_push, 4) >> 5) & 1U) != 0U; } } + } - // Handle cruise enabled - if ((addr == 0x30f) && (bus == (nissan_alt_eps ? 1 : 2))) { - bool cruise_engaged = (GET_BYTE(to_push, 0) >> 3) & 1U; - pcm_cruise_check(cruise_engaged); - } - - generic_rx_checks((addr == 0x169) && (bus == 0)); + // Handle cruise enabled + if ((addr == 0x30f) && (bus == (nissan_alt_eps ? 1 : 2))) { + bool cruise_engaged = (GET_BYTE(to_push, 0) >> 3) & 1U; + pcm_cruise_check(cruise_engaged); } - return valid; -} + generic_rx_checks((addr == 0x169) && (bus == 0)); +} -static int nissan_tx_hook(CANPacket_t *to_send) { - int tx = 1; +static bool nissan_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; - if (!msg_allowed(to_send, NISSAN_TX_MSGS, sizeof(NISSAN_TX_MSGS) / sizeof(NISSAN_TX_MSGS[0]))) { - tx = 0; - } - // steer cmd checks if (addr == 0x169) { int desired_angle = ((GET_BYTE(to_send, 0) << 10) | (GET_BYTE(to_send, 1) << 2) | ((GET_BYTE(to_send, 2) >> 6) & 0x3U)); bool lka_active = (GET_BYTE(to_send, 6) >> 4) & 1U; // Factor is -0.01, offset is 1310. Flip to correct sign, but keep units in CAN scale - desired_angle = -desired_angle + (1310 * NISSAN_STEERING_LIMITS.angle_deg_to_can); + desired_angle = -desired_angle + (1310.0f * NISSAN_STEERING_LIMITS.angle_deg_to_can); if (steer_angle_cmd_checks(desired_angle, lka_active, NISSAN_STEERING_LIMITS)) { violation = true; @@ -131,7 +118,7 @@ static int nissan_tx_hook(CANPacket_t *to_send) { } if (violation) { - tx = 0; + tx = false; } return tx; @@ -142,7 +129,7 @@ static int nissan_fwd_hook(int bus_num, int addr) { int bus_fwd = -1; if (bus_num == 0) { - int block_msg = (addr == 0x280); // CANCEL_MSG + bool block_msg = (addr == 0x280); // CANCEL_MSG if (!block_msg) { bus_fwd = 2; // ADAS } @@ -150,7 +137,7 @@ static int nissan_fwd_hook(int bus_num, int addr) { if (bus_num == 2) { // 0x169 is LKAS, 0x2b1 LKAS_HUD, 0x4cc LKAS_HUD_INFO_MSG - int block_msg = ((addr == 0x169) || (addr == 0x2b1) || (addr == 0x4cc)); + bool block_msg = ((addr == 0x169) || (addr == 0x2b1) || (addr == 0x4cc)); if (!block_msg) { bus_fwd = 0; // V-CAN } @@ -159,15 +146,14 @@ static int nissan_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* nissan_init(uint16_t param) { +static safety_config nissan_init(uint16_t param) { nissan_alt_eps = GET_FLAG(param, NISSAN_PARAM_ALT_EPS_BUS); - return &nissan_rx_checks; + return BUILD_SAFETY_CFG(nissan_rx_checks, NISSAN_TX_MSGS); } const safety_hooks nissan_hooks = { .init = nissan_init, .rx = nissan_rx_hook, .tx = nissan_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = nissan_fwd_hook, }; diff --git a/panda/board/safety/safety_subaru.h b/panda/board/safety/safety_subaru.h index bfe800142a..c445bc435e 100644 --- a/panda/board/safety/safety_subaru.h +++ b/panda/board/safety/safety_subaru.h @@ -73,47 +73,39 @@ const LongitudinalLimits SUBARU_LONG_LIMITS = { {MSG_SUBARU_ES_STATIC_1, SUBARU_MAIN_BUS, 8}, \ {MSG_SUBARU_ES_STATIC_2, SUBARU_MAIN_BUS, 8}, \ -#define SUBARU_COMMON_ADDR_CHECKS(alt_bus) \ - {.msg = {{MSG_SUBARU_Throttle, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_Steering_Torque, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_Wheel_Speeds, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_Brake_Status, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_CruiseControl, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 50000U}, { 0 }, { 0 }}}, \ +#define SUBARU_COMMON_RX_CHECKS(alt_bus) \ + {.msg = {{MSG_SUBARU_Throttle, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, \ + {.msg = {{MSG_SUBARU_Steering_Torque, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + {.msg = {{MSG_SUBARU_Wheel_Speeds, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + {.msg = {{MSG_SUBARU_Brake_Status, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ + {.msg = {{MSG_SUBARU_CruiseControl, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 20U}, { 0 }, { 0 }}}, \ const CanMsg SUBARU_TX_MSGS[] = { SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) }; -#define SUBARU_TX_MSGS_LEN (sizeof(SUBARU_TX_MSGS) / sizeof(SUBARU_TX_MSGS[0])) const CanMsg SUBARU_LONG_TX_MSGS[] = { SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) SUBARU_COMMON_LONG_TX_MSGS(SUBARU_MAIN_BUS) }; -#define SUBARU_LONG_TX_MSGS_LEN (sizeof(SUBARU_LONG_TX_MSGS) / sizeof(SUBARU_LONG_TX_MSGS[0])) const CanMsg SUBARU_GEN2_TX_MSGS[] = { SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) }; -#define SUBARU_GEN2_TX_MSGS_LEN (sizeof(SUBARU_GEN2_TX_MSGS) / sizeof(SUBARU_GEN2_TX_MSGS[0])) const CanMsg SUBARU_GEN2_LONG_TX_MSGS[] = { SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) SUBARU_COMMON_LONG_TX_MSGS(SUBARU_ALT_BUS) SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() }; -#define SUBARU_GEN2_LONG_TX_MSGS_LEN (sizeof(SUBARU_GEN2_LONG_TX_MSGS) / sizeof(SUBARU_GEN2_LONG_TX_MSGS[0])) -AddrCheckStruct subaru_addr_checks[] = { - SUBARU_COMMON_ADDR_CHECKS(SUBARU_MAIN_BUS) +RxCheck subaru_rx_checks[] = { + SUBARU_COMMON_RX_CHECKS(SUBARU_MAIN_BUS) }; -#define SUBARU_ADDR_CHECK_LEN (sizeof(subaru_addr_checks) / sizeof(subaru_addr_checks[0])) -addr_checks subaru_rx_checks = {subaru_addr_checks, SUBARU_ADDR_CHECK_LEN}; -AddrCheckStruct subaru_gen2_addr_checks[] = { - SUBARU_COMMON_ADDR_CHECKS(SUBARU_ALT_BUS) +RxCheck subaru_gen2_rx_checks[] = { + SUBARU_COMMON_RX_CHECKS(SUBARU_ALT_BUS) }; -#define SUBARU_GEN2_ADDR_CHECK_LEN (sizeof(subaru_gen2_addr_checks) / sizeof(subaru_gen2_addr_checks[0])) -addr_checks subaru_gen2_rx_checks = {subaru_gen2_addr_checks, SUBARU_GEN2_ADDR_CHECK_LEN}; const uint16_t SUBARU_PARAM_GEN2 = 1; @@ -123,15 +115,15 @@ bool subaru_gen2 = false; bool subaru_longitudinal = false; -static uint32_t subaru_get_checksum(CANPacket_t *to_push) { +static uint32_t subaru_get_checksum(const CANPacket_t *to_push) { return (uint8_t)GET_BYTE(to_push, 0); } -static uint8_t subaru_get_counter(CANPacket_t *to_push) { +static uint8_t subaru_get_counter(const CANPacket_t *to_push) { return (uint8_t)(GET_BYTE(to_push, 1) & 0xFU); } -static uint32_t subaru_compute_checksum(CANPacket_t *to_push) { +static uint32_t subaru_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U); @@ -141,82 +133,63 @@ static uint32_t subaru_compute_checksum(CANPacket_t *to_push) { return checksum; } -static int subaru_rx_hook(CANPacket_t *to_push) { +static void subaru_rx_hook(const CANPacket_t *to_push) { + const int bus = GET_BUS(to_push); + const int alt_main_bus = subaru_gen2 ? SUBARU_ALT_BUS : SUBARU_MAIN_BUS; - bool valid = addr_safety_check(to_push, &subaru_rx_checks, - subaru_get_checksum, subaru_compute_checksum, subaru_get_counter, NULL); - - if (valid) { - const int bus = GET_BUS(to_push); - const int alt_main_bus = subaru_gen2 ? SUBARU_ALT_BUS : SUBARU_MAIN_BUS; - - int addr = GET_ADDR(to_push); - if ((addr == MSG_SUBARU_Steering_Torque) && (bus == SUBARU_MAIN_BUS)) { - int torque_driver_new; - torque_driver_new = ((GET_BYTES(to_push, 0, 4) >> 16) & 0x7FFU); - torque_driver_new = -1 * to_signed(torque_driver_new, 11); - update_sample(&torque_driver, torque_driver_new); - - int angle_meas_new = (GET_BYTES(to_push, 4, 2) & 0xFFFFU); - // convert Steering_Torque -> Steering_Angle to centidegrees, to match the ES_LKAS_ANGLE angle request units - angle_meas_new = ROUND(to_signed(angle_meas_new, 16) * -2.17); - update_sample(&angle_meas, angle_meas_new); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - if ((addr == MSG_SUBARU_CruiseControl) && (bus == alt_main_bus)) { - bool cruise_engaged = GET_BIT(to_push, 41U) != 0U; - pcm_cruise_check(cruise_engaged); - } + int addr = GET_ADDR(to_push); + if ((addr == MSG_SUBARU_Steering_Torque) && (bus == SUBARU_MAIN_BUS)) { + int torque_driver_new; + torque_driver_new = ((GET_BYTES(to_push, 0, 4) >> 16) & 0x7FFU); + torque_driver_new = -1 * to_signed(torque_driver_new, 11); + update_sample(&torque_driver, torque_driver_new); + + int angle_meas_new = (GET_BYTES(to_push, 4, 2) & 0xFFFFU); + // convert Steering_Torque -> Steering_Angle to centidegrees, to match the ES_LKAS_ANGLE angle request units + angle_meas_new = ROUND(to_signed(angle_meas_new, 16) * -2.17); + update_sample(&angle_meas, angle_meas_new); + } - // update vehicle moving with any non-zero wheel speed - if ((addr == MSG_SUBARU_Wheel_Speeds) && (bus == alt_main_bus)) { - uint32_t fr = (GET_BYTES(to_push, 1, 3) >> 4) & 0x1FFFU; - uint32_t rr = (GET_BYTES(to_push, 3, 3) >> 1) & 0x1FFFU; - uint32_t rl = (GET_BYTES(to_push, 4, 3) >> 6) & 0x1FFFU; - uint32_t fl = (GET_BYTES(to_push, 6, 2) >> 3) & 0x1FFFU; + // enter controls on rising edge of ACC, exit controls on ACC off + if ((addr == MSG_SUBARU_CruiseControl) && (bus == alt_main_bus)) { + bool cruise_engaged = GET_BIT(to_push, 41U); + pcm_cruise_check(cruise_engaged); + } - vehicle_moving = (fr > 0U) || (rr > 0U) || (rl > 0U) || (fl > 0U); + // update vehicle moving with any non-zero wheel speed + if ((addr == MSG_SUBARU_Wheel_Speeds) && (bus == alt_main_bus)) { + uint32_t fr = (GET_BYTES(to_push, 1, 3) >> 4) & 0x1FFFU; + uint32_t rr = (GET_BYTES(to_push, 3, 3) >> 1) & 0x1FFFU; + uint32_t rl = (GET_BYTES(to_push, 4, 3) >> 6) & 0x1FFFU; + uint32_t fl = (GET_BYTES(to_push, 6, 2) >> 3) & 0x1FFFU; - float speed = (fr + rr + rl + fl) / 4U * 0.057; - update_sample(&vehicle_speed, ROUND(speed * VEHICLE_SPEED_FACTOR)); - } + vehicle_moving = (fr > 0U) || (rr > 0U) || (rl > 0U) || (fl > 0U); - if ((addr == MSG_SUBARU_Brake_Status) && (bus == alt_main_bus)) { - brake_pressed = GET_BIT(to_push, 62U) != 0U; - } + UPDATE_VEHICLE_SPEED((fr + rr + rl + fl) / 4U * 0.057); + } - if ((addr == MSG_SUBARU_Throttle) && (bus == SUBARU_MAIN_BUS)) { - gas_pressed = GET_BYTE(to_push, 4) != 0U; - } + if ((addr == MSG_SUBARU_Brake_Status) && (bus == alt_main_bus)) { + brake_pressed = GET_BIT(to_push, 62U); + } - generic_rx_checks((addr == MSG_SUBARU_ES_LKAS) && (bus == SUBARU_MAIN_BUS)); + if ((addr == MSG_SUBARU_Throttle) && (bus == SUBARU_MAIN_BUS)) { + gas_pressed = GET_BYTE(to_push, 4) != 0U; } - return valid; -} -static int subaru_tx_hook(CANPacket_t *to_send) { + generic_rx_checks((addr == MSG_SUBARU_ES_LKAS) && (bus == SUBARU_MAIN_BUS)); +} - int tx = 1; +static bool subaru_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; - if (subaru_gen2 && subaru_longitudinal) { - tx = msg_allowed(to_send, SUBARU_GEN2_LONG_TX_MSGS, SUBARU_GEN2_LONG_TX_MSGS_LEN); - } else if (subaru_gen2) { - tx = msg_allowed(to_send, SUBARU_GEN2_TX_MSGS, SUBARU_GEN2_TX_MSGS_LEN); - } else if (subaru_longitudinal) { - tx = msg_allowed(to_send, SUBARU_LONG_TX_MSGS, SUBARU_LONG_TX_MSGS_LEN); - } else { - tx = msg_allowed(to_send, SUBARU_TX_MSGS, SUBARU_TX_MSGS_LEN); - } - // steer cmd checks if (addr == MSG_SUBARU_ES_LKAS) { int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 16) & 0x1FFFU); desired_torque = -1 * to_signed(desired_torque, 13); - bool steer_req = GET_BIT(to_send, 29U) != 0U; + bool steer_req = GET_BIT(to_send, 29U); const SteeringLimits limits = subaru_gen2 ? SUBARU_GEN2_STEERING_LIMITS : SUBARU_STEERING_LIMITS; violation |= steer_torque_cmd_checks(desired_torque, steer_req, limits); @@ -230,8 +203,8 @@ static int subaru_tx_hook(CANPacket_t *to_send) { // check es_distance cruise_throttle limits if (addr == MSG_SUBARU_ES_Distance) { - int cruise_throttle = (GET_BYTES(to_send, 2, 2) & 0xFFFU); - bool cruise_cancel = GET_BIT(to_send, 56U) != 0U; + int cruise_throttle = (GET_BYTES(to_send, 2, 2) & 0x1FFFU); + bool cruise_cancel = GET_BIT(to_send, 56U); if (subaru_longitudinal) { violation |= longitudinal_gas_checks(cruise_throttle, SUBARU_LONG_LIMITS); @@ -245,7 +218,7 @@ static int subaru_tx_hook(CANPacket_t *to_send) { // check es_status transmission_rpm limits if (addr == MSG_SUBARU_ES_Status) { - int transmission_rpm = (GET_BYTES(to_send, 2, 2) & 0xFFFU); + int transmission_rpm = (GET_BYTES(to_send, 2, 2) & 0x1FFFU); violation |= longitudinal_transmission_rpm_checks(transmission_rpm, SUBARU_LONG_LIMITS); } @@ -260,7 +233,7 @@ static int subaru_tx_hook(CANPacket_t *to_send) { } if (violation){ - tx = 0; + tx = false; } return tx; } @@ -292,26 +265,30 @@ static int subaru_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* subaru_init(uint16_t param) { +static safety_config subaru_init(uint16_t param) { subaru_gen2 = GET_FLAG(param, SUBARU_PARAM_GEN2); #ifdef ALLOW_DEBUG subaru_longitudinal = GET_FLAG(param, SUBARU_PARAM_LONGITUDINAL); #endif + safety_config ret; if (subaru_gen2) { - subaru_rx_checks = (addr_checks){subaru_gen2_addr_checks, SUBARU_GEN2_ADDR_CHECK_LEN}; + ret = subaru_longitudinal ? BUILD_SAFETY_CFG(subaru_gen2_rx_checks, SUBARU_GEN2_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(subaru_gen2_rx_checks, SUBARU_GEN2_TX_MSGS); } else { - subaru_rx_checks = (addr_checks){subaru_addr_checks, SUBARU_ADDR_CHECK_LEN}; + ret = subaru_longitudinal ? BUILD_SAFETY_CFG(subaru_rx_checks, SUBARU_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(subaru_rx_checks, SUBARU_TX_MSGS); } - - return &subaru_rx_checks; + return ret; } const safety_hooks subaru_hooks = { .init = subaru_init, .rx = subaru_rx_hook, .tx = subaru_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = subaru_fwd_hook, + .get_counter = subaru_get_counter, + .get_checksum = subaru_get_checksum, + .compute_checksum = subaru_compute_checksum, }; diff --git a/panda/board/safety/safety_subaru_preglobal.h b/panda/board/safety/safety_subaru_preglobal.h index 145a5cfa23..1047814ac3 100644 --- a/panda/board/safety/safety_subaru_preglobal.h +++ b/panda/board/safety/safety_subaru_preglobal.h @@ -28,29 +28,23 @@ const CanMsg SUBARU_PG_TX_MSGS[] = { {MSG_SUBARU_PG_ES_Distance, SUBARU_PG_MAIN_BUS, 8}, {MSG_SUBARU_PG_ES_LKAS, SUBARU_PG_MAIN_BUS, 8} }; -#define SUBARU_PG_TX_MSGS_LEN (sizeof(SUBARU_PG_TX_MSGS) / sizeof(SUBARU_PG_TX_MSGS[0])) // TODO: do checksum and counter checks after adding the signals to the outback dbc file -AddrCheckStruct subaru_preglobal_addr_checks[] = { - {.msg = {{MSG_SUBARU_PG_Throttle, SUBARU_PG_MAIN_BUS, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_SUBARU_PG_Steering_Torque, SUBARU_PG_MAIN_BUS, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_SUBARU_PG_CruiseControl, SUBARU_PG_MAIN_BUS, 8, .expected_timestep = 50000U}, { 0 }, { 0 }}}, +RxCheck subaru_preglobal_rx_checks[] = { + {.msg = {{MSG_SUBARU_PG_Throttle, SUBARU_PG_MAIN_BUS, 8, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MSG_SUBARU_PG_Steering_Torque, SUBARU_PG_MAIN_BUS, 8, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MSG_SUBARU_PG_CruiseControl, SUBARU_PG_MAIN_BUS, 8, .frequency = 20U}, { 0 }, { 0 }}}, }; -#define SUBARU_PG_ADDR_CHECK_LEN (sizeof(subaru_preglobal_addr_checks) / sizeof(subaru_preglobal_addr_checks[0])) -addr_checks subaru_preglobal_rx_checks = {subaru_preglobal_addr_checks, SUBARU_PG_ADDR_CHECK_LEN}; const int SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE = 1; bool subaru_pg_reversed_driver_torque = false; -static int subaru_preglobal_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &subaru_preglobal_rx_checks, NULL, NULL, NULL, NULL); - +static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) { const int bus = GET_BUS(to_push); - if (valid && (bus == SUBARU_PG_MAIN_BUS)) { + if (bus == SUBARU_PG_MAIN_BUS) { int addr = GET_ADDR(to_push); if (addr == MSG_SUBARU_PG_Steering_Torque) { int torque_driver_new; @@ -62,7 +56,7 @@ static int subaru_preglobal_rx_hook(CANPacket_t *to_push) { // enter controls on rising edge of ACC, exit controls on ACC off if (addr == MSG_SUBARU_PG_CruiseControl) { - bool cruise_engaged = GET_BIT(to_push, 49U) != 0U; + bool cruise_engaged = GET_BIT(to_push, 49U); pcm_cruise_check(cruise_engaged); } @@ -81,27 +75,21 @@ static int subaru_preglobal_rx_hook(CANPacket_t *to_push) { generic_rx_checks((addr == MSG_SUBARU_PG_ES_LKAS)); } - return valid; } -static int subaru_preglobal_tx_hook(CANPacket_t *to_send) { - - int tx = 1; +static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); - if (!msg_allowed(to_send, SUBARU_PG_TX_MSGS, SUBARU_PG_TX_MSGS_LEN)) { - tx = 0; - } - // steer cmd checks if (addr == MSG_SUBARU_PG_ES_LKAS) { int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 8) & 0x1FFFU); desired_torque = -1 * to_signed(desired_torque, 13); - bool steer_req = (GET_BIT(to_send, 24U) != 0U); + bool steer_req = GET_BIT(to_send, 24U); if (steer_torque_cmd_checks(desired_torque, steer_req, SUBARU_PG_STEERING_LIMITS)) { - tx = 0; + tx = false; } } @@ -116,7 +104,7 @@ static int subaru_preglobal_fwd_hook(int bus_num, int addr) { } if (bus_num == SUBARU_PG_CAM_BUS) { - int block_msg = ((addr == MSG_SUBARU_PG_ES_Distance) || (addr == MSG_SUBARU_PG_ES_LKAS)); + bool block_msg = ((addr == MSG_SUBARU_PG_ES_Distance) || (addr == MSG_SUBARU_PG_ES_LKAS)); if (!block_msg) { bus_fwd = SUBARU_PG_MAIN_BUS; // Main CAN } @@ -125,15 +113,14 @@ static int subaru_preglobal_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* subaru_preglobal_init(uint16_t param) { +static safety_config subaru_preglobal_init(uint16_t param) { subaru_pg_reversed_driver_torque = GET_FLAG(param, SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE); - return &subaru_preglobal_rx_checks; + return BUILD_SAFETY_CFG(subaru_preglobal_rx_checks, SUBARU_PG_TX_MSGS); } const safety_hooks subaru_preglobal_hooks = { .init = subaru_preglobal_init, .rx = subaru_preglobal_rx_hook, .tx = subaru_preglobal_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = subaru_preglobal_fwd_hook, }; diff --git a/panda/board/safety/safety_tesla.h b/panda/board/safety/safety_tesla.h index 168ad462dc..4fa0df84aa 100644 --- a/panda/board/safety/safety_tesla.h +++ b/panda/board/safety/safety_tesla.h @@ -26,120 +26,101 @@ const CanMsg TESLA_TX_MSGS[] = { {0x45, 2, 8}, // STW_ACTN_RQ {0x2b9, 0, 8}, // DAS_control }; -#define TESLA_TX_LEN (sizeof(TESLA_TX_MSGS) / sizeof(TESLA_TX_MSGS[0])) const CanMsg TESLA_PT_TX_MSGS[] = { {0x2bf, 0, 8}, // DAS_control }; -#define TESLA_PT_TX_LEN (sizeof(TESLA_PT_TX_MSGS) / sizeof(TESLA_PT_TX_MSGS[0])) - -AddrCheckStruct tesla_addr_checks[] = { - {.msg = {{0x2b9, 2, 8, .expected_timestep = 40000U}, { 0 }, { 0 }}}, // DAS_control (25Hz) - {.msg = {{0x370, 0, 8, .expected_timestep = 40000U}, { 0 }, { 0 }}}, // EPAS_sysStatus (25Hz) - {.msg = {{0x108, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque1 (100Hz) - {.msg = {{0x118, 0, 6, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque2 (100Hz) - {.msg = {{0x20a, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, // BrakeMessage (50Hz) - {.msg = {{0x368, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // DI_state (10Hz) - {.msg = {{0x318, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // GTW_carState (10Hz) + +RxCheck tesla_rx_checks[] = { + {.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control + {.msg = {{0x370, 0, 8, .frequency = 25U}, { 0 }, { 0 }}}, // EPAS_sysStatus + {.msg = {{0x108, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1 + {.msg = {{0x118, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2 + {.msg = {{0x20a, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage + {.msg = {{0x368, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state + {.msg = {{0x318, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // GTW_carState }; -#define TESLA_ADDR_CHECK_LEN (sizeof(tesla_addr_checks) / sizeof(tesla_addr_checks[0])) -addr_checks tesla_rx_checks = {tesla_addr_checks, TESLA_ADDR_CHECK_LEN}; - -AddrCheckStruct tesla_pt_addr_checks[] = { - {.msg = {{0x106, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque1 (100Hz) - {.msg = {{0x116, 0, 6, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque2 (100Hz) - {.msg = {{0x1f8, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}}, // BrakeMessage (50Hz) - {.msg = {{0x2bf, 2, 8, .expected_timestep = 40000U}, { 0 }, { 0 }}}, // DAS_control (25Hz) - {.msg = {{0x256, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // DI_state (10Hz) + +RxCheck tesla_pt_rx_checks[] = { + {.msg = {{0x106, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1 + {.msg = {{0x116, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2 + {.msg = {{0x1f8, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage + {.msg = {{0x2bf, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control + {.msg = {{0x256, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state }; -#define TESLA_PT_ADDR_CHECK_LEN (sizeof(tesla_pt_addr_checks) / sizeof(tesla_pt_addr_checks[0])) -addr_checks tesla_pt_rx_checks = {tesla_pt_addr_checks, TESLA_PT_ADDR_CHECK_LEN}; bool tesla_longitudinal = false; bool tesla_powertrain = false; // Are we the second panda intercepting the powertrain bus? bool tesla_stock_aeb = false; -static int tesla_rx_hook(CANPacket_t *to_push) { - bool valid = addr_safety_check(to_push, tesla_powertrain ? (&tesla_pt_rx_checks) : (&tesla_rx_checks), - NULL, NULL, NULL, NULL); - - if(valid) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - if(bus == 0) { - if (!tesla_powertrain) { - if(addr == 0x370) { - // Steering angle: (0.1 * val) - 819.2 in deg. - // Store it 1/10 deg to match steering request - int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3FU) << 8) | GET_BYTE(to_push, 5)) - 8192U; - update_sample(&angle_meas, angle_meas_new); - } - } - - if(addr == (tesla_powertrain ? 0x116 : 0x118)) { - // Vehicle speed: ((0.05 * val) - 25) * MPH_TO_MPS - float speed = (((((GET_BYTE(to_push, 3) & 0x0FU) << 8) | (GET_BYTE(to_push, 2))) * 0.05) - 25) * 0.447; - vehicle_moving = ABS(speed) > 0.1; - update_sample(&vehicle_speed, ROUND(speed * VEHICLE_SPEED_FACTOR)); +static void tesla_rx_hook(const CANPacket_t *to_push) { + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); + + if(bus == 0) { + if (!tesla_powertrain) { + if(addr == 0x370) { + // Steering angle: (0.1 * val) - 819.2 in deg. + // Store it 1/10 deg to match steering request + int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3FU) << 8) | GET_BYTE(to_push, 5)) - 8192U; + update_sample(&angle_meas, angle_meas_new); } + } - if(addr == (tesla_powertrain ? 0x106 : 0x108)) { - // Gas pressed - gas_pressed = (GET_BYTE(to_push, 6) != 0U); - } + if(addr == (tesla_powertrain ? 0x116 : 0x118)) { + // Vehicle speed: ((0.05 * val) - 25) * MPH_TO_MPS + float speed = (((((GET_BYTE(to_push, 3) & 0x0FU) << 8) | (GET_BYTE(to_push, 2))) * 0.05) - 25) * 0.447; + vehicle_moving = ABS(speed) > 0.1; + UPDATE_VEHICLE_SPEED(speed); + } - if(addr == (tesla_powertrain ? 0x1f8 : 0x20a)) { - // Brake pressed - brake_pressed = (((GET_BYTE(to_push, 0) & 0x0CU) >> 2) != 1U); - } + if(addr == (tesla_powertrain ? 0x106 : 0x108)) { + // Gas pressed + gas_pressed = (GET_BYTE(to_push, 6) != 0U); + } - if(addr == (tesla_powertrain ? 0x256 : 0x368)) { - // Cruise state - int cruise_state = (GET_BYTE(to_push, 1) >> 4); - bool cruise_engaged = (cruise_state == 2) || // ENABLED - (cruise_state == 3) || // STANDSTILL - (cruise_state == 4) || // OVERRIDE - (cruise_state == 6) || // PRE_FAULT - (cruise_state == 7); // PRE_CANCEL - pcm_cruise_check(cruise_engaged); - } + if(addr == (tesla_powertrain ? 0x1f8 : 0x20a)) { + // Brake pressed + brake_pressed = (((GET_BYTE(to_push, 0) & 0x0CU) >> 2) != 1U); } - if (bus == 2) { - int das_control_addr = (tesla_powertrain ? 0x2bf : 0x2b9); - if (tesla_longitudinal && (addr == das_control_addr)) { - // "AEB_ACTIVE" - tesla_stock_aeb = ((GET_BYTE(to_push, 2) & 0x03U) == 1U); - } + if(addr == (tesla_powertrain ? 0x256 : 0x368)) { + // Cruise state + int cruise_state = (GET_BYTE(to_push, 1) >> 4); + bool cruise_engaged = (cruise_state == 2) || // ENABLED + (cruise_state == 3) || // STANDSTILL + (cruise_state == 4) || // OVERRIDE + (cruise_state == 6) || // PRE_FAULT + (cruise_state == 7); // PRE_CANCEL + pcm_cruise_check(cruise_engaged); } + } - if (tesla_powertrain) { - // 0x2bf: DAS_control should not be received on bus 0 - generic_rx_checks((addr == 0x2bf) && (bus == 0)); - } else { - // 0x488: DAS_steeringControl should not be received on bus 0 - generic_rx_checks((addr == 0x488) && (bus == 0)); + if (bus == 2) { + int das_control_addr = (tesla_powertrain ? 0x2bf : 0x2b9); + if (tesla_longitudinal && (addr == das_control_addr)) { + // "AEB_ACTIVE" + tesla_stock_aeb = ((GET_BYTE(to_push, 2) & 0x03U) == 1U); } } - return valid; -} + if (tesla_powertrain) { + // 0x2bf: DAS_control should not be received on bus 0 + generic_rx_checks((addr == 0x2bf) && (bus == 0)); + } else { + // 0x488: DAS_steeringControl should not be received on bus 0 + generic_rx_checks((addr == 0x488) && (bus == 0)); + } +} -static int tesla_tx_hook(CANPacket_t *to_send) { - int tx = 1; +static bool tesla_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; - if(!msg_allowed(to_send, - tesla_powertrain ? TESLA_PT_TX_MSGS : TESLA_TX_MSGS, - tesla_powertrain ? TESLA_PT_TX_LEN : TESLA_TX_LEN)) { - tx = 0; - } - if(!tesla_powertrain && (addr == 0x488)) { // Steering control: (0.1 * val) - 1638.35 in deg. // We use 1/10 deg as a unit here @@ -187,7 +168,7 @@ static int tesla_tx_hook(CANPacket_t *to_send) { } if (violation) { - tx = 0; + tx = false; } return tx; @@ -222,19 +203,24 @@ static int tesla_fwd_hook(int bus_num, int addr) { return bus_fwd; } -static const addr_checks* tesla_init(uint16_t param) { +static safety_config tesla_init(uint16_t param) { tesla_powertrain = GET_FLAG(param, TESLA_FLAG_POWERTRAIN); tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL); tesla_stock_aeb = false; - return tesla_powertrain ? (&tesla_pt_rx_checks) : (&tesla_rx_checks); + safety_config ret; + if (tesla_powertrain) { + ret = BUILD_SAFETY_CFG(tesla_pt_rx_checks, TESLA_PT_TX_MSGS); + } else { + ret = BUILD_SAFETY_CFG(tesla_rx_checks, TESLA_TX_MSGS); + } + return ret; } const safety_hooks tesla_hooks = { .init = tesla_init, .rx = tesla_rx_hook, .tx = tesla_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = tesla_fwd_hook, }; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index 721ce84445..50c00b38a8 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -13,8 +13,24 @@ const SteeringLimits TOYOTA_STEERING_LIMITS = { .max_invalid_request_frames = 1, .min_valid_request_rt_interval = 170000, // 170ms; a ~10% buffer on cutting every 19 frames .has_steer_req_tolerance = true, + + // LTA angle limits + // factor for STEER_TORQUE_SENSOR->STEER_ANGLE and STEERING_LTA->STEER_ANGLE_CMD (1 / 0.0573) + .angle_deg_to_can = 17.452007, + .angle_rate_up_lookup = { + {5., 25., 25.}, + {0.3, 0.15, 0.15} + }, + .angle_rate_down_lookup = { + {5., 25., 25.}, + {0.36, 0.26, 0.26} + }, }; +const int TOYOTA_LTA_MAX_ANGLE = 1657; // EPS only accepts up to 94.9461 +const int TOYOTA_LTA_MAX_MEAS_TORQUE = 1500; +const int TOYOTA_LTA_MAX_DRIVER_TORQUE = 150; + // longitudinal limits const LongitudinalLimits TOYOTA_LONG_LIMITS = { .max_accel = 2000, // 2.0 m/s2 @@ -27,35 +43,71 @@ const LongitudinalLimits TOYOTA_LONG_LIMITS = { const int TOYOTA_GAS_INTERCEPTOR_THRSLD = 805; #define TOYOTA_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks -const CanMsg TOYOTA_TX_MSGS[] = {{0x283, 0, 7}, {0x2E6, 0, 8}, {0x2E7, 0, 8}, {0x33E, 0, 7}, {0x344, 0, 8}, {0x365, 0, 7}, {0x366, 0, 7}, {0x4CB, 0, 8}, // DSU bus 0 - {0x128, 1, 6}, {0x141, 1, 4}, {0x160, 1, 8}, {0x161, 1, 7}, {0x470, 1, 4}, // DSU bus 1 - {0x2E4, 0, 5}, {0x191, 0, 8}, {0x411, 0, 8}, {0x412, 0, 8}, {0x343, 0, 8}, {0x1D2, 0, 8}, // LKAS + ACC - {0x200, 0, 6}}; // interceptor - -AddrCheckStruct toyota_addr_checks[] = { - {.msg = {{ 0xaa, 0, 8, .check_checksum = false, .expected_timestep = 12000U}, { 0 }, { 0 }}}, - {.msg = {{0x260, 0, 8, .check_checksum = true, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{0x1D2, 0, 8, .check_checksum = true, .expected_timestep = 30000U}, { 0 }, { 0 }}}, - {.msg = {{0x224, 0, 8, .check_checksum = false, .expected_timestep = 25000U}, - {0x226, 0, 8, .check_checksum = false, .expected_timestep = 25000U}, { 0 }}}, +// Stock longitudinal +#define TOYOTA_COMMON_TX_MSGS \ + {0x2E4, 0, 5}, {0x191, 0, 8}, {0x412, 0, 8}, {0x343, 0, 8}, {0x1D2, 0, 8}, /* LKAS + LTA + ACC & PCM cancel cmds */ \ + +#define TOYOTA_COMMON_LONG_TX_MSGS \ + TOYOTA_COMMON_TX_MSGS \ + {0x283, 0, 7}, {0x2E6, 0, 8}, {0x2E7, 0, 8}, {0x33E, 0, 7}, {0x344, 0, 8}, {0x365, 0, 7}, {0x366, 0, 7}, {0x4CB, 0, 8}, /* DSU bus 0 */ \ + {0x128, 1, 6}, {0x141, 1, 4}, {0x160, 1, 8}, {0x161, 1, 7}, {0x470, 1, 4}, /* DSU bus 1 */ \ + {0x411, 0, 8}, /* PCS_HUD */ \ + {0x750, 0, 8}, /* radar diagnostic address */ \ + +const CanMsg TOYOTA_TX_MSGS[] = { + TOYOTA_COMMON_TX_MSGS +}; + +const CanMsg TOYOTA_LONG_TX_MSGS[] = { + TOYOTA_COMMON_LONG_TX_MSGS +}; + +const CanMsg TOYOTA_INTERCEPTOR_TX_MSGS[] = { + TOYOTA_COMMON_LONG_TX_MSGS + {0x200, 0, 6}, // gas interceptor +}; + +#define TOYOTA_COMMON_RX_CHECKS(lta) \ + {.msg = {{ 0xaa, 0, 8, .check_checksum = false, .frequency = 83U}, { 0 }, { 0 }}}, \ + {.msg = {{0x260, 0, 8, .check_checksum = true, .quality_flag = (lta), .frequency = 50U}, { 0 }, { 0 }}}, \ + {.msg = {{0x1D2, 0, 8, .check_checksum = true, .frequency = 33U}, { 0 }, { 0 }}}, \ + {.msg = {{0x224, 0, 8, .check_checksum = false, .frequency = 40U}, \ + {0x226, 0, 8, .check_checksum = false, .frequency = 40U}, { 0 }}}, \ + +RxCheck toyota_lka_rx_checks[] = { + TOYOTA_COMMON_RX_CHECKS(false) +}; + +RxCheck toyota_lka_interceptor_rx_checks[] = { + TOYOTA_COMMON_RX_CHECKS(false) + {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, +}; + +// Check the quality flag for angle measurement when using LTA, since it's not set on TSS-P cars +RxCheck toyota_lta_rx_checks[] = { + TOYOTA_COMMON_RX_CHECKS(true) +}; + +RxCheck toyota_lta_interceptor_rx_checks[] = { + TOYOTA_COMMON_RX_CHECKS(true) + {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, }; -#define TOYOTA_ADDR_CHECKS_LEN (sizeof(toyota_addr_checks) / sizeof(toyota_addr_checks[0])) -addr_checks toyota_rx_checks = {toyota_addr_checks, TOYOTA_ADDR_CHECKS_LEN}; // safety param flags -// first byte is for eps factor, second is for flags +// first byte is for EPS factor, second is for flags const uint32_t TOYOTA_PARAM_OFFSET = 8U; -const uint32_t TOYOTA_EPS_FACTOR = (1U << TOYOTA_PARAM_OFFSET) - 1U; -const uint32_t TOYOTA_PARAM_ALT_BRAKE = 1U << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_STOCK_LONGITUDINAL = 2U << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_LTA = 4U << TOYOTA_PARAM_OFFSET; +const uint32_t TOYOTA_EPS_FACTOR = (1UL << TOYOTA_PARAM_OFFSET) - 1U; +const uint32_t TOYOTA_PARAM_ALT_BRAKE = 1UL << TOYOTA_PARAM_OFFSET; +const uint32_t TOYOTA_PARAM_STOCK_LONGITUDINAL = 2UL << TOYOTA_PARAM_OFFSET; +const uint32_t TOYOTA_PARAM_LTA = 4UL << TOYOTA_PARAM_OFFSET; +const uint32_t TOYOTA_PARAM_GAS_INTERCEPTOR = 8UL << TOYOTA_PARAM_OFFSET; bool toyota_alt_brake = false; bool toyota_stock_longitudinal = false; bool toyota_lta = false; int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file -static uint32_t toyota_compute_checksum(CANPacket_t *to_push) { +static uint32_t toyota_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U) + (uint8_t)(len); @@ -65,17 +117,34 @@ static uint32_t toyota_compute_checksum(CANPacket_t *to_push) { return checksum; } -static uint32_t toyota_get_checksum(CANPacket_t *to_push) { +static uint32_t toyota_get_checksum(const CANPacket_t *to_push) { int checksum_byte = GET_LEN(to_push) - 1U; return (uint8_t)(GET_BYTE(to_push, checksum_byte)); } -static int toyota_rx_hook(CANPacket_t *to_push) { +static uint8_t toyota_get_counter(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + + uint8_t cnt = 0U; + if (addr == 0x201) { + // Signal: COUNTER_PEDAL + cnt = GET_BYTE(to_push, 4) & 0x0FU; + } + return cnt; +} - bool valid = addr_safety_check(to_push, &toyota_rx_checks, - toyota_get_checksum, toyota_compute_checksum, NULL, NULL); +static bool toyota_get_quality_flag_valid(const CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); - if (valid && (GET_BUS(to_push) == 0U)) { + bool valid = false; + if (addr == 0x260) { + valid = !GET_BIT(to_push, 3U); // STEER_ANGLE_INITIALIZING + } + return valid; +} + +static void toyota_rx_hook(const CANPacket_t *to_push) { + if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); // get eps motor torque (0.66 factor in dbc) @@ -92,36 +161,57 @@ static int toyota_rx_hook(CANPacket_t *to_push) { // increase torque_meas by 1 to be conservative on rounding torque_meas.min--; torque_meas.max++; + + // driver torque for angle limiting + int torque_driver_new = (GET_BYTE(to_push, 1) << 8) | GET_BYTE(to_push, 2); + torque_driver_new = to_signed(torque_driver_new, 16); + update_sample(&torque_driver, torque_driver_new); + + // LTA request angle should match current angle while inactive, clipped to max accepted angle. + // note that angle can be relative to init angle on some TSS2 platforms, LTA has the same offset + bool steer_angle_initializing = GET_BIT(to_push, 3U); + if (!steer_angle_initializing) { + int angle_meas_new = (GET_BYTE(to_push, 3) << 8U) | GET_BYTE(to_push, 4); + angle_meas_new = CLAMP(to_signed(angle_meas_new, 16), -TOYOTA_LTA_MAX_ANGLE, TOYOTA_LTA_MAX_ANGLE); + update_sample(&angle_meas, angle_meas_new); + } } // enter controls on rising edge of ACC, exit controls on ACC off // exit controls on rising edge of gas press if (addr == 0x1D2) { // 5th bit is CRUISE_ACTIVE - bool cruise_engaged = GET_BIT(to_push, 5U) != 0U; + bool cruise_engaged = GET_BIT(to_push, 5U); pcm_cruise_check(cruise_engaged); // sample gas pedal - if (!gas_interceptor_detected) { - gas_pressed = GET_BIT(to_push, 4U) == 0U; + if (!enable_gas_interceptor) { + gas_pressed = !GET_BIT(to_push, 4U); } } + // sample speed if (addr == 0xaa) { - // check that all wheel speeds are at zero value with offset - bool standstill = (GET_BYTES(to_push, 0, 4) == 0x6F1A6F1AU) && (GET_BYTES(to_push, 4, 4) == 0x6F1A6F1AU); - vehicle_moving = !standstill; + int speed = 0; + // sum 4 wheel speeds. conversion: raw * 0.01 - 67.67 + for (uint8_t i = 0U; i < 8U; i += 2U) { + int wheel_speed = (GET_BYTE(to_push, i) << 8U) | GET_BYTE(to_push, (i + 1U)); + speed += wheel_speed - 6767; + } + // check that all wheel speeds are at zero value + vehicle_moving = speed != 0; + + UPDATE_VEHICLE_SPEED(speed / 4.0 * 0.01 / 3.6); } // most cars have brake_pressed on 0x226, corolla and rav4 on 0x224 if (((addr == 0x224) && toyota_alt_brake) || ((addr == 0x226) && !toyota_alt_brake)) { uint8_t bit = (addr == 0x224) ? 5U : 37U; - brake_pressed = GET_BIT(to_push, bit) != 0U; + brake_pressed = GET_BIT(to_push, bit); } // sample gas interceptor - if (addr == 0x201) { - gas_interceptor_detected = 1; + if ((addr == 0x201) && enable_gas_interceptor) { int gas_interceptor = TOYOTA_GET_INTERCEPTOR(to_push); gas_pressed = gas_interceptor > TOYOTA_GAS_INTERCEPTOR_THRSLD; @@ -129,28 +219,26 @@ static int toyota_rx_hook(CANPacket_t *to_push) { gas_interceptor_prev = gas_interceptor; } - generic_rx_checks((addr == 0x2E4)); + bool stock_ecu_detected = addr == 0x2E4; // STEERING_LKA + if (!toyota_stock_longitudinal && (addr == 0x343)) { + stock_ecu_detected = true; // ACC_CONTROL + } + generic_rx_checks(stock_ecu_detected); } - return valid; } -static int toyota_tx_hook(CANPacket_t *to_send) { - - int tx = 1; +static bool toyota_tx_hook(const CANPacket_t *to_send) { + bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); - if (!msg_allowed(to_send, TOYOTA_TX_MSGS, sizeof(TOYOTA_TX_MSGS)/sizeof(TOYOTA_TX_MSGS[0]))) { - tx = 0; - } - // Check if msg is sent on BUS 0 if (bus == 0) { // GAS PEDAL: safety check if (addr == 0x200) { if (longitudinal_interceptor_checks(to_send)) { - tx = 0; + tx = false; } } @@ -164,7 +252,7 @@ static int toyota_tx_hook(CANPacket_t *to_send) { // only ACC messages that cancel are allowed when openpilot is not controlling longitudinal if (toyota_stock_longitudinal) { - bool cancel_req = GET_BIT(to_send, 24U) != 0U; + bool cancel_req = GET_BIT(to_send, 24U); if (!cancel_req) { violation = true; } @@ -174,7 +262,7 @@ static int toyota_tx_hook(CANPacket_t *to_send) { } if (violation) { - tx = 0; + tx = false; } } @@ -183,23 +271,55 @@ static int toyota_tx_hook(CANPacket_t *to_send) { // only allow the checksum, which is the last byte bool block = (GET_BYTES(to_send, 0, 4) != 0U) || (GET_BYTE(to_send, 4) != 0U) || (GET_BYTE(to_send, 5) != 0U); if (block) { - tx = 0; + tx = false; } } - // LTA steering check - // only sent to prevent dash errors, no actuation is accepted + // LTA angle steering check if (addr == 0x191) { - // check the STEER_REQUEST, STEER_REQUEST_2, SETME_X64 STEER_ANGLE_CMD signals - bool lta_request = GET_BIT(to_send, 0U) != 0U; - bool lta_request2 = GET_BIT(to_send, 25U) != 0U; - int setme_x64 = GET_BYTE(to_send, 5); + // check the STEER_REQUEST, STEER_REQUEST_2, TORQUE_WIND_DOWN, STEER_ANGLE_CMD signals + bool lta_request = GET_BIT(to_send, 0U); + bool lta_request2 = GET_BIT(to_send, 25U); + int torque_wind_down = GET_BYTE(to_send, 5); int lta_angle = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2); lta_angle = to_signed(lta_angle, 16); - // block LTA msgs with actuation requests - if (lta_request || lta_request2 || (lta_angle != 0) || (setme_x64 != 0)) { - tx = 0; + bool steer_control_enabled = lta_request || lta_request2; + if (!toyota_lta) { + // using torque (LKA), block LTA msgs with actuation requests + if (steer_control_enabled || (lta_angle != 0) || (torque_wind_down != 0)) { + tx = false; + } + } else { + // check angle rate limits and inactive angle + if (steer_angle_cmd_checks(lta_angle, steer_control_enabled, TOYOTA_STEERING_LIMITS)) { + tx = false; + } + + if (lta_request != lta_request2) { + tx = false; + } + + // TORQUE_WIND_DOWN is gated on steer request + if (!steer_control_enabled && (torque_wind_down != 0)) { + tx = false; + } + + // TORQUE_WIND_DOWN can only be no or full torque + if ((torque_wind_down != 0) && (torque_wind_down != 100)) { + tx = false; + } + + // check if we should wind down torque + int driver_torque = MIN(ABS(torque_driver.min), ABS(torque_driver.max)); + if ((driver_torque > TOYOTA_LTA_MAX_DRIVER_TORQUE) && (torque_wind_down != 0)) { + tx = false; + } + + int eps_torque = MIN(ABS(torque_meas.min), ABS(torque_meas.max)); + if ((eps_torque > TOYOTA_LTA_MAX_MEAS_TORQUE) && (torque_wind_down != 0)) { + tx = false; + } } } @@ -207,31 +327,60 @@ static int toyota_tx_hook(CANPacket_t *to_send) { if (addr == 0x2E4) { int desired_torque = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2); desired_torque = to_signed(desired_torque, 16); - bool steer_req = GET_BIT(to_send, 0U) != 0U; - if (steer_torque_cmd_checks(desired_torque, steer_req, TOYOTA_STEERING_LIMITS)) { - tx = 0; - } + bool steer_req = GET_BIT(to_send, 0U); // When using LTA (angle control), assert no actuation on LKA message - if (toyota_lta && ((desired_torque != 0) || steer_req)) { - tx = 0; + if (!toyota_lta) { + if (steer_torque_cmd_checks(desired_torque, steer_req, TOYOTA_STEERING_LIMITS)) { + tx = false; + } + } else { + if ((desired_torque != 0) || steer_req) { + tx = false; + } } } } + // UDS: Only tester present ("\x0F\x02\x3E\x00\x00\x00\x00\x00") allowed on diagnostics address + if (addr == 0x750) { + // this address is sub-addressed. only allow tester present to radar (0xF) + bool invalid_uds_msg = (GET_BYTES(to_send, 0, 4) != 0x003E020FU) || (GET_BYTES(to_send, 4, 4) != 0x0U); + if (invalid_uds_msg) { + tx = 0; + } + } + return tx; } -static const addr_checks* toyota_init(uint16_t param) { +static safety_config toyota_init(uint16_t param) { toyota_alt_brake = GET_FLAG(param, TOYOTA_PARAM_ALT_BRAKE); toyota_stock_longitudinal = GET_FLAG(param, TOYOTA_PARAM_STOCK_LONGITUDINAL); + toyota_lta = GET_FLAG(param, TOYOTA_PARAM_LTA); + enable_gas_interceptor = GET_FLAG(param, TOYOTA_PARAM_GAS_INTERCEPTOR); toyota_dbc_eps_torque_factor = param & TOYOTA_EPS_FACTOR; -#ifdef ALLOW_DEBUG - toyota_lta = GET_FLAG(param, TOYOTA_PARAM_LTA); -#else - toyota_lta = false; -#endif - return &toyota_rx_checks; + // Gas interceptor should not be used if openpilot is not controlling longitudinal + if (toyota_stock_longitudinal) { + enable_gas_interceptor = false; + } + + safety_config ret; + if (toyota_stock_longitudinal) { + SET_TX_MSGS(TOYOTA_TX_MSGS, ret); + } else { + enable_gas_interceptor ? SET_TX_MSGS(TOYOTA_INTERCEPTOR_TX_MSGS, ret) : \ + SET_TX_MSGS(TOYOTA_LONG_TX_MSGS, ret); + } + + if (enable_gas_interceptor) { + toyota_lta ? SET_RX_CHECKS(toyota_lta_interceptor_rx_checks, ret) : \ + SET_RX_CHECKS(toyota_lka_interceptor_rx_checks, ret); + } else { + toyota_lta ? SET_RX_CHECKS(toyota_lta_rx_checks, ret) : \ + SET_RX_CHECKS(toyota_lka_rx_checks, ret); + } + return ret; } static int toyota_fwd_hook(int bus_num, int addr) { @@ -245,10 +394,10 @@ static int toyota_fwd_hook(int bus_num, int addr) { if (bus_num == 2) { // block stock lkas messages and stock acc messages (if OP is doing ACC) // in TSS2, 0x191 is LTA which we need to block to avoid controls collision - int is_lkas_msg = ((addr == 0x2E4) || (addr == 0x412) || (addr == 0x191)); + bool is_lkas_msg = ((addr == 0x2E4) || (addr == 0x412) || (addr == 0x191)); // in TSS2 the camera does ACC as well, so filter 0x343 - int is_acc_msg = (addr == 0x343); - int block_msg = is_lkas_msg || (is_acc_msg && !toyota_stock_longitudinal); + bool is_acc_msg = (addr == 0x343); + bool block_msg = is_lkas_msg || (is_acc_msg && !toyota_stock_longitudinal); if (!block_msg) { bus_fwd = 0; } @@ -261,6 +410,9 @@ const safety_hooks toyota_hooks = { .init = toyota_init, .rx = toyota_rx_hook, .tx = toyota_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = toyota_fwd_hook, + .get_checksum = toyota_get_checksum, + .compute_checksum = toyota_compute_checksum, + .get_counter = toyota_get_counter, + .get_quality_flag_valid = toyota_get_quality_flag_valid, }; diff --git a/panda/board/safety/safety_volkswagen_mqb.h b/panda/board/safety/safety_volkswagen_mqb.h index a88e4a9e81..d880a69a6e 100644 --- a/panda/board/safety/safety_volkswagen_mqb.h +++ b/panda/board/safety/safety_volkswagen_mqb.h @@ -34,35 +34,35 @@ const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS = { #define MSG_LDW_02 0x397 // TX by OP, Lane line recognition and text alerts // Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration -const CanMsg VOLKSWAGEN_MQB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8}, {MSG_LDW_02, 0, 8}}; -const CanMsg VOLKSWAGEN_MQB_LONG_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_LDW_02, 0, 8}, +const CanMsg VOLKSWAGEN_MQB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8}, + {MSG_LDW_02, 0, 8}, {MSG_LH_EPS_03, 2, 8}}; +const CanMsg VOLKSWAGEN_MQB_LONG_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_LDW_02, 0, 8}, {MSG_LH_EPS_03, 2, 8}, {MSG_ACC_02, 0, 8}, {MSG_ACC_06, 0, 8}, {MSG_ACC_07, 0, 8}}; -AddrCheckStruct volkswagen_mqb_addr_checks[] = { - {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_14, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 100000U}, { 0 }, { 0 }}}, +RxCheck volkswagen_mqb_rx_checks[] = { + {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_14, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{MSG_GRA_ACC_01, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 33U}, { 0 }, { 0 }}}, }; -#define VOLKSWAGEN_MQB_ADDR_CHECKS_LEN (sizeof(volkswagen_mqb_addr_checks) / sizeof(volkswagen_mqb_addr_checks[0])) -addr_checks volkswagen_mqb_rx_checks = {volkswagen_mqb_addr_checks, VOLKSWAGEN_MQB_ADDR_CHECKS_LEN}; uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F, aka 8H2F/AUTOSAR bool volkswagen_mqb_brake_pedal_switch = false; bool volkswagen_mqb_brake_pressure_detected = false; -static uint32_t volkswagen_mqb_get_checksum(CANPacket_t *to_push) { +static uint32_t volkswagen_mqb_get_checksum(const CANPacket_t *to_push) { return (uint8_t)GET_BYTE(to_push, 0); } -static uint8_t volkswagen_mqb_get_counter(CANPacket_t *to_push) { +static uint8_t volkswagen_mqb_get_counter(const CANPacket_t *to_push) { // MQB message counters are consistently found at LSB 8. return (uint8_t)GET_BYTE(to_push, 1) & 0xFU; } -static uint32_t volkswagen_mqb_compute_crc(CANPacket_t *to_push) { +static uint32_t volkswagen_mqb_compute_crc(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); @@ -84,14 +84,17 @@ static uint32_t volkswagen_mqb_compute_crc(CANPacket_t *to_push) { crc ^= (uint8_t[]){0xC4,0xE2,0x4F,0xE4,0xF8,0x2F,0x56,0x81,0x9F,0xE5,0x83,0x44,0x05,0x3F,0x97,0xDF}[counter]; } else if (addr == MSG_MOTOR_20) { crc ^= (uint8_t[]){0xE9,0x65,0xAE,0x6B,0x7B,0x35,0xE5,0x5F,0x4E,0xC7,0x86,0xA2,0xBB,0xDD,0xEB,0xB4}[counter]; - } else { // Undefined CAN message, CRC check expected to fail + } else if (addr == MSG_GRA_ACC_01) { + crc ^= (uint8_t[]){0x6A,0x38,0xB4,0x27,0x22,0xEF,0xE1,0xBB,0xF8,0x80,0x84,0x49,0xC7,0x9E,0x1E,0x2B}[counter]; + } else { + // Undefined CAN message, CRC check expected to fail } crc = volkswagen_crc8_lut_8h2f[crc]; return (uint8_t)(crc ^ 0xFFU); } -static const addr_checks* volkswagen_mqb_init(uint16_t param) { +static safety_config volkswagen_mqb_init(uint16_t param) { UNUSED(param); volkswagen_set_button_prev = false; @@ -103,15 +106,12 @@ static const addr_checks* volkswagen_mqb_init(uint16_t param) { volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL); #endif gen_crc_lookup_table_8(0x2F, volkswagen_crc8_lut_8h2f); - return &volkswagen_mqb_rx_checks; + return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_STOCK_TX_MSGS); } -static int volkswagen_mqb_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &volkswagen_mqb_rx_checks, - volkswagen_mqb_get_checksum, volkswagen_mqb_compute_crc, volkswagen_mqb_get_counter, NULL); - - if (valid && (GET_BUS(to_push) == 0U)) { +static void volkswagen_mqb_rx_hook(const CANPacket_t *to_push) { + if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); // Update in-motion state by sampling wheel speeds @@ -170,7 +170,7 @@ static int volkswagen_mqb_rx_hook(CANPacket_t *to_push) { } // Always exit controls on rising edge of Cancel // Signal: GRA_ACC_01.GRA_Abbrechen - if (GET_BIT(to_push, 13U) == 1U) { + if (GET_BIT(to_push, 13U)) { controls_allowed = false; } } @@ -194,18 +194,11 @@ static int volkswagen_mqb_rx_hook(CANPacket_t *to_push) { generic_rx_checks((addr == MSG_HCA_01)); } - return valid; } -static int volkswagen_mqb_tx_hook(CANPacket_t *to_send) { +static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) { int addr = GET_ADDR(to_send); - int tx = 1; - - if (volkswagen_longitudinal) { - tx = msg_allowed(to_send, VOLKSWAGEN_MQB_LONG_TX_MSGS, sizeof(VOLKSWAGEN_MQB_LONG_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_LONG_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, VOLKSWAGEN_MQB_STOCK_TX_MSGS, sizeof(VOLKSWAGEN_MQB_STOCK_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_STOCK_TX_MSGS[0])); - } + bool tx = true; // Safety check for HCA_01 Heading Control Assist torque // Signal: HCA_01.HCA_01_LM_Offset (absolute torque) @@ -217,10 +210,10 @@ static int volkswagen_mqb_tx_hook(CANPacket_t *to_send) { desired_torque *= -1; } - bool steer_req = GET_BIT(to_send, 30U) != 0U; + bool steer_req = GET_BIT(to_send, 30U); if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_MQB_STEERING_LIMITS)) { - tx = 0; + tx = false; } } @@ -244,7 +237,7 @@ static int volkswagen_mqb_tx_hook(CANPacket_t *to_send) { violation |= longitudinal_accel_checks(desired_accel, VOLKSWAGEN_MQB_LONG_LIMITS); if (violation) { - tx = 0; + tx = false; } } @@ -253,11 +246,10 @@ static int volkswagen_mqb_tx_hook(CANPacket_t *to_send) { if ((addr == MSG_GRA_ACC_01) && !controls_allowed) { // disallow resume and set: bits 16 and 19 if ((GET_BYTE(to_send, 2) & 0x9U) != 0U) { - tx = 0; + tx = false; } } - // 1 allows the message through return tx; } @@ -266,8 +258,13 @@ static int volkswagen_mqb_fwd_hook(int bus_num, int addr) { switch (bus_num) { case 0: - // Forward all traffic from the Extended CAN onward - bus_fwd = 2; + if (addr == MSG_LH_EPS_03) { + // openpilot needs to replace apparent driver steering input torque to pacify VW Emergency Assist + bus_fwd = -1; + } else { + // Forward all remaining traffic from Extended CAN onward + bus_fwd = 2; + } break; case 2: if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) { @@ -294,6 +291,8 @@ const safety_hooks volkswagen_mqb_hooks = { .init = volkswagen_mqb_init, .rx = volkswagen_mqb_rx_hook, .tx = volkswagen_mqb_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = volkswagen_mqb_fwd_hook, + .get_counter = volkswagen_mqb_get_counter, + .get_checksum = volkswagen_mqb_get_checksum, + .compute_checksum = volkswagen_mqb_compute_crc, }; diff --git a/panda/board/safety/safety_volkswagen_pq.h b/panda/board/safety/safety_volkswagen_pq.h index 6232bdf569..1922cf4671 100644 --- a/panda/board/safety/safety_volkswagen_pq.h +++ b/panda/board/safety/safety_volkswagen_pq.h @@ -37,24 +37,22 @@ const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, const CanMsg VOLKSWAGEN_PQ_LONG_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8}, {MSG_ACC_SYSTEM, 0, 8}, {MSG_ACC_GRA_ANZEIGE, 0, 8}}; -AddrCheckStruct volkswagen_pq_addr_checks[] = { - {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_BREMSE_1, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_5, 0, 8, .check_checksum = true, .max_counter = 0U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_GRA_NEU, 0, 4, .check_checksum = true, .max_counter = 15U, .expected_timestep = 33000U}, { 0 }, { 0 }}}, +RxCheck volkswagen_pq_rx_checks[] = { + {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MSG_BREMSE_1, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_5, 0, 8, .check_checksum = true, .max_counter = 0U, .frequency = 50U}, { 0 }, { 0 }}}, + {.msg = {{MSG_GRA_NEU, 0, 4, .check_checksum = true, .max_counter = 15U, .frequency = 30U}, { 0 }, { 0 }}}, }; -#define VOLKSWAGEN_PQ_ADDR_CHECKS_LEN (sizeof(volkswagen_pq_addr_checks) / sizeof(volkswagen_pq_addr_checks[0])) -addr_checks volkswagen_pq_rx_checks = {volkswagen_pq_addr_checks, VOLKSWAGEN_PQ_ADDR_CHECKS_LEN}; -static uint32_t volkswagen_pq_get_checksum(CANPacket_t *to_push) { +static uint32_t volkswagen_pq_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); return (uint32_t)GET_BYTE(to_push, (addr == MSG_MOTOR_5) ? 7 : 0); } -static uint8_t volkswagen_pq_get_counter(CANPacket_t *to_push) { +static uint8_t volkswagen_pq_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); uint8_t counter = 0U; @@ -68,7 +66,7 @@ static uint8_t volkswagen_pq_get_counter(CANPacket_t *to_push) { return counter; } -static uint32_t volkswagen_pq_compute_checksum(CANPacket_t *to_push) { +static uint32_t volkswagen_pq_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); uint8_t checksum = 0U; @@ -84,7 +82,7 @@ static uint32_t volkswagen_pq_compute_checksum(CANPacket_t *to_push) { return checksum; } -static const addr_checks* volkswagen_pq_init(uint16_t param) { +static safety_config volkswagen_pq_init(uint16_t param) { UNUSED(param); volkswagen_set_button_prev = false; @@ -93,15 +91,12 @@ static const addr_checks* volkswagen_pq_init(uint16_t param) { #ifdef ALLOW_DEBUG volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL); #endif - return &volkswagen_pq_rx_checks; + return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_LONG_TX_MSGS) : \ + BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_STOCK_TX_MSGS); } -static int volkswagen_pq_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &volkswagen_pq_rx_checks, - volkswagen_pq_get_checksum, volkswagen_pq_compute_checksum, volkswagen_pq_get_counter, NULL); - - if (valid && (GET_BUS(to_push) == 0U)) { +static void volkswagen_pq_rx_hook(const CANPacket_t *to_push) { + if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); // Update in-motion state from speed value. @@ -146,7 +141,7 @@ static int volkswagen_pq_rx_hook(CANPacket_t *to_push) { volkswagen_resume_button_prev = resume_button; // Exit controls on rising edge of Cancel, override Set/Resume if present simultaneously // Signal: GRA_ACC_01.GRA_Abbrechen - if (GET_BIT(to_push, 9U) == 1U) { + if (GET_BIT(to_push, 9U)) { controls_allowed = false; } } @@ -172,18 +167,11 @@ static int volkswagen_pq_rx_hook(CANPacket_t *to_push) { generic_rx_checks((addr == MSG_HCA_1)); } - return valid; } -static int volkswagen_pq_tx_hook(CANPacket_t *to_send) { +static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) { int addr = GET_ADDR(to_send); - int tx = 1; - - if (volkswagen_longitudinal) { - tx = msg_allowed(to_send, VOLKSWAGEN_PQ_LONG_TX_MSGS, sizeof(VOLKSWAGEN_PQ_LONG_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_LONG_TX_MSGS[0])); - } else { - tx = msg_allowed(to_send, VOLKSWAGEN_PQ_STOCK_TX_MSGS, sizeof(VOLKSWAGEN_PQ_STOCK_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_STOCK_TX_MSGS[0])); - } + bool tx = true; // Safety check for HCA_1 Heading Control Assist torque // Signal: HCA_1.LM_Offset (absolute torque) @@ -200,7 +188,7 @@ static int volkswagen_pq_tx_hook(CANPacket_t *to_send) { bool steer_req = (hca_status == 5U); if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_PQ_STEERING_LIMITS)) { - tx = 0; + tx = false; } } @@ -211,7 +199,7 @@ static int volkswagen_pq_tx_hook(CANPacket_t *to_send) { int desired_accel = ((((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) * 5U) - 7220U; if (longitudinal_accel_checks(desired_accel, VOLKSWAGEN_PQ_LONG_LIMITS)) { - tx = 0; + tx = false; } } @@ -221,11 +209,10 @@ static int volkswagen_pq_tx_hook(CANPacket_t *to_send) { // Signal: GRA_Neu.GRA_Neu_Setzen // Signal: GRA_Neu.GRA_Neu_Recall if (GET_BIT(to_send, 16U) || GET_BIT(to_send, 17U)) { - tx = 0; + tx = false; } } - // 1 allows the message through return tx; } @@ -261,6 +248,8 @@ const safety_hooks volkswagen_pq_hooks = { .init = volkswagen_pq_init, .rx = volkswagen_pq_rx_hook, .tx = volkswagen_pq_tx_hook, - .tx_lin = nooutput_tx_lin_hook, .fwd = volkswagen_pq_fwd_hook, + .get_counter = volkswagen_pq_get_counter, + .get_checksum = volkswagen_pq_get_checksum, + .compute_checksum = volkswagen_pq_compute_checksum, }; diff --git a/panda/board/safety_declarations.h b/panda/board/safety_declarations.h index cbef3a25d4..64b55f2033 100644 --- a/panda/board/safety_declarations.h +++ b/panda/board/safety_declarations.h @@ -1,15 +1,21 @@ #pragma once -#define GET_BIT(msg, b) (((msg)->data[((b) / 8U)] >> ((b) % 8U)) & 0x1U) +#define GET_BIT(msg, b) ((bool)!!(((msg)->data[((b) / 8U)] >> ((b) % 8U)) & 0x1U)) #define GET_BYTE(msg, b) ((msg)->data[(b)]) #define GET_FLAG(value, mask) (((__typeof__(mask))(value) & (mask)) == (mask)) -#define SET_ADDR_CHECKS(name) ((addr_checks){(name), (sizeof((name)) / sizeof((name)[0]))}) +#define BUILD_SAFETY_CFG(rx, tx) ((safety_config){(rx), (sizeof((rx)) / sizeof((rx)[0])), \ + (tx), (sizeof((tx)) / sizeof((tx)[0]))}) +#define SET_RX_CHECKS(rx, config) ((config).rx_checks = (rx), \ + (config).rx_checks_len = sizeof((rx)) / sizeof((rx)[0])) +#define SET_TX_MSGS(tx, config) ((config).tx_msgs = (tx), \ + (config).tx_msgs_len = sizeof((tx)) / sizeof((tx)[0])) +#define UPDATE_VEHICLE_SPEED(val_ms) (update_sample(&vehicle_speed, ROUND((val_ms) * VEHICLE_SPEED_FACTOR))) uint32_t GET_BYTES(const CANPacket_t *msg, int start, int len) { uint32_t ret = 0U; for (int i = 0; i < len; i++) { - const uint8_t shift = i * 8; + const uint32_t shift = i * 8; ret |= (((uint32_t)msg->data[start + i]) << shift); } return ret; @@ -22,6 +28,7 @@ const uint8_t MAX_MISSED_MSGS = 10U; // used to represent floating point vehicle speed in a sample_t #define VEHICLE_SPEED_FACTOR 100.0 + // sample struct that keeps 6 samples in memory struct sample_t { int values[MAX_SAMPLE_VALS]; @@ -109,14 +116,11 @@ typedef struct { const bool check_checksum; // true is checksum check is performed const uint8_t max_counter; // maximum value of the counter. 0 means that the counter check is skipped const bool quality_flag; // true is quality flag check is performed - const uint32_t expected_timestep; // expected time between message updates [us] + const uint32_t frequency; // expected frequency of the message [Hz] } CanMsgCheck; -// params and flags about checksum, counter and frequency checks for each monitored address typedef struct { - // const params - const CanMsgCheck msg[MAX_ADDR_CHECK_MSGS]; // check either messages (e.g. honda steer) - // dynamic flags + // dynamic flags, reset on safety mode init bool msg_seen; int index; // if multiple messages are allowed to be checked, this stores the index of the first one seen. only msg[msg_index] will be used bool valid_checksum; // true if and only if checksum check is passed @@ -125,16 +129,44 @@ typedef struct { uint8_t last_counter; // last counter value uint32_t last_timestamp; // micro-s bool lagging; // true if and only if the time between updates is excessive -} AddrCheckStruct; +} RxStatus; +// params and flags about checksum, counter and frequency checks for each monitored address typedef struct { - AddrCheckStruct *check; - int len; -} addr_checks; + const CanMsgCheck msg[MAX_ADDR_CHECK_MSGS]; // check either messages (e.g. honda steer) + RxStatus status; +} RxCheck; + +typedef struct { + RxCheck *rx_checks; + int rx_checks_len; + const CanMsg *tx_msgs; + int tx_msgs_len; +} safety_config; + +typedef uint32_t (*get_checksum_t)(const CANPacket_t *to_push); +typedef uint32_t (*compute_checksum_t)(const CANPacket_t *to_push); +typedef uint8_t (*get_counter_t)(const CANPacket_t *to_push); +typedef bool (*get_quality_flag_valid_t)(const CANPacket_t *to_push); + +typedef safety_config (*safety_hook_init)(uint16_t param); +typedef void (*rx_hook)(const CANPacket_t *to_push); +typedef bool (*tx_hook)(const CANPacket_t *to_send); +typedef int (*fwd_hook)(int bus_num, int addr); + +typedef struct { + safety_hook_init init; + rx_hook rx; + tx_hook tx; + fwd_hook fwd; + get_checksum_t get_checksum; + compute_checksum_t compute_checksum; + get_counter_t get_counter; + get_quality_flag_valid_t get_quality_flag_valid; +} safety_hooks; -int safety_rx_hook(CANPacket_t *to_push); -int safety_tx_hook(CANPacket_t *to_send); -int safety_tx_lin_hook(int lin_num, uint8_t *data, int len); +bool safety_rx_hook(const CANPacket_t *to_push); +bool safety_tx_hook(CANPacket_t *to_send); uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last); int to_signed(int d, int bits); void update_sample(struct sample_t *sample, int sample_new); @@ -144,7 +176,7 @@ bool angle_dist_to_meas_check(int val, struct sample_t *val_meas, const int MAX_ERROR, const int MAX_VAL); bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR); -bool driver_limit_check(int val, int val_last, struct sample_t *val_driver, +bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver, const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ALLOWANCE, const int DRIVER_FACTOR); bool get_longitudinal_allowed(void); @@ -153,17 +185,14 @@ float interpolate(struct lookup_t xy, float x); int ROUND(float val); void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]); void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]); -bool msg_allowed(CANPacket_t *to_send, const CanMsg msg_list[], int len); -int get_addr_check_index(CANPacket_t *to_push, AddrCheckStruct addr_list[], const int len); -void update_counter(AddrCheckStruct addr_list[], int index, uint8_t counter); -void update_addr_timestamp(AddrCheckStruct addr_list[], int index); -bool is_msg_valid(AddrCheckStruct addr_list[], int index); -bool addr_safety_check(CANPacket_t *to_push, - const addr_checks *rx_checks, - uint32_t (*get_checksum)(CANPacket_t *to_push), - uint32_t (*compute_checksum)(CANPacket_t *to_push), - uint8_t (*get_counter)(CANPacket_t *to_push), - bool (*get_quality_flag_valid)(CANPacket_t *to_push)); +bool msg_allowed(const CANPacket_t *to_send, const CanMsg msg_list[], int len); +int get_addr_check_index(const CANPacket_t *to_push, RxCheck addr_list[], const int len); +void update_counter(RxCheck addr_list[], int index, uint8_t counter); +void update_addr_timestamp(RxCheck addr_list[], int index); +bool is_msg_valid(RxCheck addr_list[], int index); +bool rx_msg_safety_check(const CANPacket_t *to_push, + const safety_config *cfg, + const safety_hooks *safety_hooks); void generic_rx_checks(bool stock_ecu_detected); void relay_malfunction_set(void); void relay_malfunction_reset(void); @@ -174,29 +203,15 @@ bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limit bool longitudinal_gas_checks(int desired_gas, const LongitudinalLimits limits); bool longitudinal_transmission_rpm_checks(int desired_transmission_rpm, const LongitudinalLimits limits); bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limits); -bool longitudinal_interceptor_checks(CANPacket_t *to_send); +bool longitudinal_interceptor_checks(const CANPacket_t *to_send); void pcm_cruise_check(bool cruise_engaged); -typedef const addr_checks* (*safety_hook_init)(uint16_t param); -typedef int (*rx_hook)(CANPacket_t *to_push); -typedef int (*tx_hook)(CANPacket_t *to_send); -typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len); -typedef int (*fwd_hook)(int bus_num, int addr); - -typedef struct { - safety_hook_init init; - rx_hook rx; - tx_hook tx; - tx_lin_hook tx_lin; - fwd_hook fwd; -} safety_hooks; - -void safety_tick(const addr_checks *addr_checks); +void safety_tick(const safety_config *safety_config); // This can be set by the safety hooks bool controls_allowed = false; bool relay_malfunction = false; -bool gas_interceptor_detected = false; +bool enable_gas_interceptor = false; int gas_interceptor_prev = 0; bool gas_pressed = false; bool gas_pressed_prev = false; @@ -245,6 +260,9 @@ struct sample_t angle_meas; // last 6 steer angles/curvatures // See ISO 15622:2018 for more information. #define ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX 8 +// This flag allows AEB to be commanded from openpilot. +#define ALT_EXP_ALLOW_AEB 16 + int alternative_experience = 0; // time since safety mode has been changed diff --git a/panda/board/stm32fx/board.h b/panda/board/stm32fx/board.h index 76593a5294..808f773829 100644 --- a/panda/board/stm32fx/board.h +++ b/panda/board/stm32fx/board.h @@ -7,49 +7,35 @@ // ///// Board definition and detection ///// // #include "stm32fx/lladc.h" #include "drivers/harness.h" -#ifdef PANDA - #include "drivers/fan.h" - #include "stm32fx/llfan.h" - #include "stm32fx/llrtc.h" - #include "drivers/rtc.h" - #include "drivers/clock_source.h" - #include "boards/white.h" - #include "boards/grey.h" - #include "boards/black.h" - #include "boards/uno.h" - #include "boards/dos.h" -#else - #include "boards/pedal.h" -#endif +#include "drivers/fan.h" +#include "stm32fx/llfan.h" +#include "stm32fx/llrtc.h" +#include "drivers/rtc.h" +#include "drivers/clock_source.h" +#include "boards/white.h" +#include "boards/grey.h" +#include "boards/black.h" +#include "boards/uno.h" +#include "boards/dos.h" void detect_board_type(void) { - #ifdef PANDA - // SPI lines floating: white (TODO: is this reliable? Not really, we have to enable ESP/GPS to be able to detect this on the UART) - set_gpio_output(GPIOC, 14, 1); - set_gpio_output(GPIOC, 5, 1); - if(!detect_with_pull(GPIOB, 1, PULL_UP) && !detect_with_pull(GPIOB, 7, PULL_UP)){ - hw_type = HW_TYPE_DOS; - current_board = &board_dos; - } else if((detect_with_pull(GPIOA, 4, PULL_DOWN)) || (detect_with_pull(GPIOA, 5, PULL_DOWN)) || (detect_with_pull(GPIOA, 6, PULL_DOWN)) || (detect_with_pull(GPIOA, 7, PULL_DOWN))){ - hw_type = HW_TYPE_WHITE_PANDA; - current_board = &board_white; - } else if(detect_with_pull(GPIOA, 13, PULL_DOWN)) { // Rev AB deprecated, so no pullup means black. In REV C, A13 is pulled up to 5V with a 10K - hw_type = HW_TYPE_GREY_PANDA; - current_board = &board_grey; - } else if(!detect_with_pull(GPIOB, 15, PULL_UP)) { - hw_type = HW_TYPE_UNO; - current_board = &board_uno; - } else { - hw_type = HW_TYPE_BLACK_PANDA; - current_board = &board_black; - } - #else - #ifdef PEDAL - hw_type = HW_TYPE_PEDAL; - current_board = &board_pedal; - #else - hw_type = HW_TYPE_UNKNOWN; - print("Hardware type is UNKNOWN!\n"); - #endif - #endif + // SPI lines floating: white (TODO: is this reliable? Not really, we have to enable ESP/GPS to be able to detect this on the UART) + set_gpio_output(GPIOC, 14, 1); + set_gpio_output(GPIOC, 5, 1); + if(!detect_with_pull(GPIOB, 1, PULL_UP) && !detect_with_pull(GPIOB, 7, PULL_UP)){ + hw_type = HW_TYPE_DOS; + current_board = &board_dos; + } else if((detect_with_pull(GPIOA, 4, PULL_DOWN)) || (detect_with_pull(GPIOA, 5, PULL_DOWN)) || (detect_with_pull(GPIOA, 6, PULL_DOWN)) || (detect_with_pull(GPIOA, 7, PULL_DOWN))){ + hw_type = HW_TYPE_WHITE_PANDA; + current_board = &board_white; + } else if(detect_with_pull(GPIOA, 13, PULL_DOWN)) { // Rev AB deprecated, so no pullup means black. In REV C, A13 is pulled up to 5V with a 10K + hw_type = HW_TYPE_GREY_PANDA; + current_board = &board_grey; + } else if(!detect_with_pull(GPIOB, 15, PULL_UP)) { + hw_type = HW_TYPE_UNO; + current_board = &board_uno; + } else { + hw_type = HW_TYPE_BLACK_PANDA; + current_board = &board_black; + } } diff --git a/panda/board/stm32fx/inc/stm32f205xx.h b/panda/board/stm32fx/inc/stm32f205xx.h deleted file mode 100644 index 368bcf39e8..0000000000 --- a/panda/board/stm32fx/inc/stm32f205xx.h +++ /dev/null @@ -1,7668 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f205xx.h - * @author MCD Application Team - * @version V2.1.2 - * @date 29-June-2016 - * @brief CMSIS STM32F205xx Device Peripheral Access Layer Header File. - * This file contains : - * - Data structures and the address mapping for all peripherals - * - Peripherals registers declarations and bits definition - * - Macros to access peripheral's registers hardware - * - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f205xx - * @{ - */ - -#ifndef __STM32F205xx_H -#define __STM32F205xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M3 Processor and Core Peripherals - */ -#define __CM3_REV 0x0200U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F2XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F2XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F2XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M3 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ - CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ - CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - HASH_RNG_IRQn = 80 /*!< Hash and RNG global interrupt */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm3.h" -#include "system_stm32f2xx.h" -#include - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ - __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ - __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ - __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ - __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ - __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ - __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ -} ADC_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ - __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ - __IO uint32_t CDR; /*!< ADC common regular data register for dual - AND triple modes, Address offset: ADC1 base address + 0x308 */ -} ADC_Common_TypeDef; - - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ - __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ - __IO uint32_t TDLR; /*!< CAN mailbox data low register */ - __IO uint32_t TDHR; /*!< CAN mailbox data high register */ -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ - __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ - __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ - __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ - __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ - __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ - __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ - __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ - __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ - __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ - __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ - uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ - CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ - uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ - __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ - __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ - uint32_t RESERVED2; /*!< Reserved, 0x208 */ - __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ - uint32_t RESERVED3; /*!< Reserved, 0x210 */ - __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ - uint32_t RESERVED4; /*!< Reserved, 0x218 */ - __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ - uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ - CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ -} CAN_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - uint8_t RESERVED0; /*!< Reserved, 0x05 */ - uint16_t RESERVED1; /*!< Reserved, 0x06 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ -} CRC_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ - __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ -}DBGMCU_TypeDef; - - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ - __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ - __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ - __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ - __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ - __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ - __IO uint32_t OPTCR; /*!< FLASH option control register, Address offset: 0x14 */ -} FLASH_TypeDef; - - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FSMC_Bank1E_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ - uint32_t RESERVED1; /*!< Reserved, 0x78 */ - uint32_t RESERVED2; /*!< Reserved, 0x7C */ - __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED3; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FSMC_Bank2_3_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank4 - */ - -typedef struct -{ - __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ - __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ - __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ - __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ - __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ -} FSMC_Bank4_TypeDef; - - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ - __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ - __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ - __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ - __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ - __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ - __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ -} IWDG_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ - __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ - __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ - uint32_t RESERVED2; /*!< Reserved, 0x3C */ - __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ - uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, 0x5C */ - __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ - uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ - __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ - __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ - __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ - -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - uint32_t RESERVED1; /*!< Reserved, 0x28 */ - uint32_t RESERVED2; /*!< Reserved, 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - uint32_t RESERVED3; /*!< Reserved, 0x38 */ - uint32_t RESERVED4; /*!< Reserved, 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - uint32_t RESERVED5; /*!< Reserved, 0x44 */ - uint32_t RESERVED6; /*!< Reserved, 0x48 */ - uint32_t RESERVED7; /*!< Reserved, 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ -} RTC_TypeDef; - - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ - __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ - __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ - __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ - __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ - __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ - __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ - __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ - __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ - uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ - __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ - __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ - __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ - __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ - __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ - __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ - __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ - __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ -} SPI_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ -} RNG_TypeDef; - - - -/** - * @brief __USB_OTG_Core_register - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register Address offset : 0x00 */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register Address offset : 0x04 */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register Address offset : 0x08 */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register Address offset : 0x0C */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register Address offset : 0x10 */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register Address offset : 0x14 */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register Address offset : 0x18 */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register Address offset : 0x1C */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register Address offset : 0x20 */ - __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register Address offset : 0x24 */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register Address offset : 0x28 */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg Address offset : 0x2C */ - uint32_t Reserved30[2]; /* Reserved Address offset : 0x30 */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register Address offset : 0x38 */ - __IO uint32_t CID; /*!< User ID Register Address offset : 0x3C */ - uint32_t Reserved40[48]; /*!< Reserved Address offset : 0x40-0xFF */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg Address offset : 0x100 */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} -USB_OTG_GlobalTypeDef; - - - -/** - * @brief __device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register Address offset : 0x800 */ - __IO uint32_t DCTL; /*!< dev Control Register Address offset : 0x804 */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) Address offset : 0x808 */ - uint32_t Reserved0C; /*!< Reserved Address offset : 0x80C */ - __IO uint32_t DIEPMSK; /* !< dev IN Endpoint Mask Address offset : 0x810 */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask Address offset : 0x814 */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg Address offset : 0x818 */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask Address offset : 0x81C */ - uint32_t Reserved20; /*!< Reserved Address offset : 0x820 */ - uint32_t Reserved9; /*!< Reserved Address offset : 0x824 */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register Address offset : 0x828 */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register Address offset : 0x82C */ - __IO uint32_t DTHRCTL; /*!< dev thr Address offset : 0x830 */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk Address offset : 0x834 */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt Address offset : 0x838 */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk Address offset : 0x83C */ - uint32_t Reserved40; /*!< dedicated EP mask Address offset : 0x840 */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask Address offset : 0x844 */ - uint32_t Reserved44[15]; /*!< Reserved Address offset : 0x844-0x87C */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk Address offset : 0x884 */ -} -USB_OTG_DeviceTypeDef; - - -/** - * @brief __IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /* Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /* Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} -USB_OTG_INEndpointTypeDef; - - -/** - * @brief __OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ - uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/ - __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ - uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ - __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ - __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ - uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ -} -USB_OTG_OUTEndpointTypeDef; - - -/** - * @brief __Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /* Host Configuration Register 400h*/ - __IO uint32_t HFIR; /* Host Frame Interval Register 404h*/ - __IO uint32_t HFNUM; /* Host Frame Nbr/Frame Remaining 408h*/ - uint32_t Reserved40C; /* Reserved 40Ch*/ - __IO uint32_t HPTXSTS; /* Host Periodic Tx FIFO/ Queue Status 410h*/ - __IO uint32_t HAINT; /* Host All Channels Interrupt Register 414h*/ - __IO uint32_t HAINTMSK; /* Host All Channels Interrupt Mask 418h*/ -} -USB_OTG_HostTypeDef; - - -/** - * @brief __Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; - __IO uint32_t HCSPLT; - __IO uint32_t HCINT; - __IO uint32_t HCINTMSK; - __IO uint32_t HCTSIZ; - __IO uint32_t HCDMA; - uint32_t Reserved[2]; -} -USB_OTG_HostChannelTypeDef; - - -/** - * @brief Peripheral_memory_map - */ -#define FLASH_BASE 0x08000000U /*!< FLASH(up to 1 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000U /*!< SRAM1(112 KB) base address in the alias region */ -#define SRAM2_BASE 0x2001C000U /*!< SRAM2(16 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000U /*!< Peripheral base address in the alias region */ -#define BKPSRAM_BASE 0x40024000U /*!< Backup SRAM(4 KB) base address in the alias region */ -#define FSMC_R_BASE 0xA0000000U /*!< FSMC registers base address */ -#define SRAM1_BB_BASE 0x22000000U /*!< SRAM1(112 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22380000U /*!< SRAM2(16 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000U /*!< Peripheral base address in the bit-band region */ -#define BKPSRAM_BB_BASE 0x42480000U /*!< Backup SRAM(4 KB) base address in the bit-band region */ -#define FLASH_END 0x080FFFFFU /*!< FLASH end address */ - -/* Legacy defines */ -#define SRAM_BASE SRAM1_BASE -#define SRAM_BB_BASE SRAM1_BB_BASE - - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000U) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000U) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000U) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000U) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400U) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800U) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00U) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000U) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400U) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800U) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00U) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000U) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800U) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00U) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000U) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800U) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00U) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400U) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800U) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00U) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000U) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400U) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800U) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00U) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400U) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800U) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000U) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400U) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000U) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400U) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000U) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400U) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000U) -#define ADC2_BASE (APB2PERIPH_BASE + 0x2100U) -#define ADC3_BASE (APB2PERIPH_BASE + 0x2200U) -#define ADC_BASE (APB2PERIPH_BASE + 0x2300U) -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00U) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000U) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800U) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00U) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000U) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400U) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800U) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000U) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400U) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800U) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00U) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000U) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400U) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800U) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00U) -#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000U) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000U) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800U) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00U) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000U) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010U) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028U) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040U) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058U) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070U) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088U) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0U) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8U) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400U) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010U) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028U) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040U) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058U) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070U) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088U) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0U) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8U) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800U) - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000U) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104U) -#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060U) -#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0U) - -/* Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000U - -/*!< USB registers base address */ -#define USB_OTG_HS_PERIPH_BASE 0x40040000U -#define USB_OTG_FS_PERIPH_BASE 0x50000000U - -#define USB_OTG_GLOBAL_BASE 0x000U -#define USB_OTG_DEVICE_BASE 0x800U -#define USB_OTG_IN_ENDPOINT_BASE 0x900U -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00U -#define USB_OTG_EP_REG_SIZE 0x20U -#define USB_OTG_HOST_BASE 0x400U -#define USB_OTG_HOST_PORT_BASE 0x440U -#define USB_OTG_HOST_CHANNEL_BASE 0x500U -#define USB_OTG_HOST_CHANNEL_SIZE 0x20U -#define USB_OTG_PCGCCTL_BASE 0xE00U -#define USB_OTG_FIFO_BASE 0x1000U -#define USB_OTG_FIFO_SIZE 0x1000U - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define ADC ((ADC_Common_TypeDef *) ADC_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) -#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) - -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) -#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************** Bit definition for ADC_SR register ********************/ -#define ADC_SR_AWD 0x00000001U /*!
© COPYRIGHT(c) 2016 STMicroelectronics
- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f2xx - * @{ - */ - -#ifndef __STM32F2xx_H -#define __STM32F2xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32F2) -#define STM32F2 -#endif /* STM32F2 */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ -/* #if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) */ - - /* #define STM32F205xx */ /*!< STM32F205RG, STM32F205VG, STM32F205ZG, STM32F205RF, STM32F205VF, STM32F205ZF, - STM32F205RE, STM32F205VE, STM32F205ZE, STM32F205RC, STM32F205VC, STM32F205ZC, - STM32F205RB and STM32F205VB Devices */ - /* #define STM32F215xx */ /*!< STM32F215RG, STM32F215VG, STM32F215ZG, STM32F215RE, STM32F215VE and STM32F215ZE Devices */ - /* #define STM32F207xx */ /*!< STM32F207VG, STM32F207ZG, STM32F207IG, STM32F207VF, STM32F207ZF, STM32F207IF, - STM32F207VE, STM32F207ZE, STM32F207IE, STM32F207VC, STM32F207ZC and STM32F207IC Devices */ - /* #define STM32F217xx */ /*!< STM32F217VG, STM32F217ZG, STM32F217IG, STM32F217VE, STM32F217ZE and STM32F217IE Devices */ - -//#endif - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS Device version number V2.1.2 - */ -#define __STM32F2xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ -#define __STM32F2xx_CMSIS_VERSION_SUB1 (0x01U) /*!< [23:16] sub1 version */ -#define __STM32F2xx_CMSIS_VERSION_SUB2 (0x02U) /*!< [15:8] sub2 version */ -#define __STM32F2xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F2xx_CMSIS_VERSION ((__STM32F2xx_CMSIS_VERSION_MAIN << 24)\ - |(__STM32F2xx_CMSIS_VERSION_SUB1 << 16)\ - |(__STM32F2xx_CMSIS_VERSION_SUB2 << 8 )\ - |(__STM32F2xx_CMSIS_VERSION)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -#if defined(STM32F215xx) - #include "stm32f215xx.h" -#elif defined(STM32F205xx) - #include "stm32f205xx.h" -// #elif defined(STM32F207xx) -// #include "stm32f207xx.h" -// #elif defined(STM32F217xx) -// #include "stm32f217xx.h" -#else - #error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - ERROR = 0, - SUCCESS = !ERROR -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macro - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32f2xx_hal.h" -#endif /* USE_HAL_DRIVER */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __STM32F2xx_H */ - -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f2xx_hal_def.h b/panda/board/stm32fx/inc/stm32f2xx_hal_def.h deleted file mode 100644 index dfef07939c..0000000000 --- a/panda/board/stm32fx/inc/stm32f2xx_hal_def.h +++ /dev/null @@ -1,181 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f2xx_hal_def.h - * @author MCD Application Team - * @version V1.1.3 - * @date 29-June-2016 - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F2xx_HAL_DEF -#define __STM32F2xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f2xx.h" -//#include "Legacy/stm32_hal_legacy.h" -//#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00U, - HAL_ERROR = 0x01U, - HAL_BUSY = 0x02U, - HAL_TIMEOUT = 0x03U -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00U, - HAL_LOCKED = 0x01U -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD_, __DMA_HANDLE_) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD_ = &(__DMA_HANDLE_); \ - (__DMA_HANDLE_).Parent = (__HANDLE__); \ - } while(0) - -#define UNUSED(x) ((void)(x)) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__: specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) - -#if (USE_RTOS == 1) - /* Reserved for future use */ - #error " USE_RTOS should be 0 in the current HAL release " -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0) -#endif /* USE_RTOS */ - -#if defined ( __GNUC__ ) - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__GNUC__) /* GNU Compiler */ - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || defined ( __GNUC__ ) -/* ARM & GNUCompiler - ---------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F2xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h b/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h deleted file mode 100644 index 7cef9a648b..0000000000 --- a/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h +++ /dev/null @@ -1,299 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f2xx_hal_gpio_ex.h - * @author MCD Application Team - * @version V1.1.3 - * @date 29-June-2016 - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F2xx_HAL_GPIO_EX_H -#define __STM32F2xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f2xx_hal_def.h" - -/** @addtogroup STM32F2xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection - * @{ - */ - -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0xAU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0xAU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#if defined(STM32F207xx) || defined(STM32F217xx) -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ -#endif /* STM32F207xx || STM32F217xx */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0xCU) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xCU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0xCU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#if defined(STM32F207xx) || defined(STM32F217xx) -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ -#endif /* STM32F207xx || STM32F217xx */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U :\ - ((__GPIOx__) == (GPIOI))? 8U : 9U) -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -#if defined(STM32F207xx) || defined(STM32F217xx) - -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) -#else /* STM32F207xx || STM32F217xx */ -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) -#endif /* STM32F207xx || STM32F217xx */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F2xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/system_stm32f2xx.h b/panda/board/stm32fx/inc/system_stm32f2xx.h deleted file mode 100644 index cd4b83c570..0000000000 --- a/panda/board/stm32fx/inc/system_stm32f2xx.h +++ /dev/null @@ -1,122 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f2xx.h - * @author MCD Application Team - * @version V2.1.2 - * @date 29-June-2016 - * @brief CMSIS Cortex-M3 Device System Source File for STM32F2xx devices. -****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f2xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F2XX_H -#define __SYSTEM_STM32F2XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F2xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F2xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - - -/** - * @} - */ - -/** @addtogroup STM32F2xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F2xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F2xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F2XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/interrupt_handlers.h b/panda/board/stm32fx/interrupt_handlers.h index 3b40f4ee52..41d7427d71 100644 --- a/panda/board/stm32fx/interrupt_handlers.h +++ b/panda/board/stm32fx/interrupt_handlers.h @@ -1,5 +1,5 @@ // ********************* Bare interrupt handlers ********************* -// Only implemented the STM32F413 interrupts for now, the STM32F203 specific ones do not fall into the scope of SIL2 +// Only implemented the STM32F413 interrupts for now void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} void PVD_IRQHandler(void) {handle_interrupt(PVD_IRQn);} @@ -73,28 +73,26 @@ void DMA2_Stream7_IRQHandler(void) {handle_interrupt(DMA2_Stream7_IRQn);} void USART6_IRQHandler(void) {handle_interrupt(USART6_IRQn);} void I2C3_EV_IRQHandler(void) {handle_interrupt(I2C3_EV_IRQn);} void I2C3_ER_IRQHandler(void) {handle_interrupt(I2C3_ER_IRQn);} -#ifdef STM32F4 - void DFSDM1_FLT0_IRQHandler(void) {handle_interrupt(DFSDM1_FLT0_IRQn);} - void DFSDM1_FLT1_IRQHandler(void) {handle_interrupt(DFSDM1_FLT1_IRQn);} - void CAN3_TX_IRQHandler(void) {handle_interrupt(CAN3_TX_IRQn);} - void CAN3_RX0_IRQHandler(void) {handle_interrupt(CAN3_RX0_IRQn);} - void CAN3_RX1_IRQHandler(void) {handle_interrupt(CAN3_RX1_IRQn);} - void CAN3_SCE_IRQHandler(void) {handle_interrupt(CAN3_SCE_IRQn);} - void RNG_IRQHandler(void) {handle_interrupt(RNG_IRQn);} - void FPU_IRQHandler(void) {handle_interrupt(FPU_IRQn);} - void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} - void UART8_IRQHandler(void) {handle_interrupt(UART8_IRQn);} - void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} - void SPI5_IRQHandler(void) {handle_interrupt(SPI5_IRQn);} - void SAI1_IRQHandler(void) {handle_interrupt(SAI1_IRQn);} - void UART9_IRQHandler(void) {handle_interrupt(UART9_IRQn);} - void UART10_IRQHandler(void) {handle_interrupt(UART10_IRQn);} - void QUADSPI_IRQHandler(void) {handle_interrupt(QUADSPI_IRQn);} - void FMPI2C1_EV_IRQHandler(void) {handle_interrupt(FMPI2C1_EV_IRQn);} - void FMPI2C1_ER_IRQHandler(void) {handle_interrupt(FMPI2C1_ER_IRQn);} - void LPTIM1_IRQHandler(void) {handle_interrupt(LPTIM1_IRQn);} - void DFSDM2_FLT0_IRQHandler(void) {handle_interrupt(DFSDM2_FLT0_IRQn);} - void DFSDM2_FLT1_IRQHandler(void) {handle_interrupt(DFSDM2_FLT1_IRQn);} - void DFSDM2_FLT2_IRQHandler(void) {handle_interrupt(DFSDM2_FLT2_IRQn);} - void DFSDM2_FLT3_IRQHandler(void) {handle_interrupt(DFSDM2_FLT3_IRQn);} -#endif +void DFSDM1_FLT0_IRQHandler(void) {handle_interrupt(DFSDM1_FLT0_IRQn);} +void DFSDM1_FLT1_IRQHandler(void) {handle_interrupt(DFSDM1_FLT1_IRQn);} +void CAN3_TX_IRQHandler(void) {handle_interrupt(CAN3_TX_IRQn);} +void CAN3_RX0_IRQHandler(void) {handle_interrupt(CAN3_RX0_IRQn);} +void CAN3_RX1_IRQHandler(void) {handle_interrupt(CAN3_RX1_IRQn);} +void CAN3_SCE_IRQHandler(void) {handle_interrupt(CAN3_SCE_IRQn);} +void RNG_IRQHandler(void) {handle_interrupt(RNG_IRQn);} +void FPU_IRQHandler(void) {handle_interrupt(FPU_IRQn);} +void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} +void UART8_IRQHandler(void) {handle_interrupt(UART8_IRQn);} +void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} +void SPI5_IRQHandler(void) {handle_interrupt(SPI5_IRQn);} +void SAI1_IRQHandler(void) {handle_interrupt(SAI1_IRQn);} +void UART9_IRQHandler(void) {handle_interrupt(UART9_IRQn);} +void UART10_IRQHandler(void) {handle_interrupt(UART10_IRQn);} +void QUADSPI_IRQHandler(void) {handle_interrupt(QUADSPI_IRQn);} +void FMPI2C1_EV_IRQHandler(void) {handle_interrupt(FMPI2C1_EV_IRQn);} +void FMPI2C1_ER_IRQHandler(void) {handle_interrupt(FMPI2C1_ER_IRQn);} +void LPTIM1_IRQHandler(void) {handle_interrupt(LPTIM1_IRQn);} +void DFSDM2_FLT0_IRQHandler(void) {handle_interrupt(DFSDM2_FLT0_IRQn);} +void DFSDM2_FLT1_IRQHandler(void) {handle_interrupt(DFSDM2_FLT1_IRQn);} +void DFSDM2_FLT2_IRQHandler(void) {handle_interrupt(DFSDM2_FLT2_IRQn);} +void DFSDM2_FLT3_IRQHandler(void) {handle_interrupt(DFSDM2_FLT3_IRQn);} diff --git a/panda/board/stm32fx/lladc.h b/panda/board/stm32fx/lladc.h index 31c17f4b25..c2df10f1b1 100644 --- a/panda/board/stm32fx/lladc.h +++ b/panda/board/stm32fx/lladc.h @@ -1,12 +1,3 @@ -// ACCEL1 = ADC10 -// ACCEL2 = ADC11 -// VOLT_S = ADC12 -// CURR_S = ADC13 - -#define ADCCHAN_ACCEL0 10 -#define ADCCHAN_ACCEL1 11 -#define ADCCHAN_VIN 12 -#define ADCCHAN_CURRENT 13 void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask); diff --git a/panda/board/stm32fx/llbxcan.h b/panda/board/stm32fx/llbxcan.h index fd344913f7..72523cf1bc 100644 --- a/panda/board/stm32fx/llbxcan.h +++ b/panda/board/stm32fx/llbxcan.h @@ -75,7 +75,7 @@ bool llcan_set_speed(CAN_TypeDef *CANx, uint32_t speed, bool loopback, bool sile return ret; } -void llcan_irq_disable(CAN_TypeDef *CANx) { +void llcan_irq_disable(const CAN_TypeDef *CANx) { if (CANx == CAN1) { NVIC_DisableIRQ(CAN1_TX_IRQn); NVIC_DisableIRQ(CAN1_RX0_IRQn); @@ -84,17 +84,15 @@ void llcan_irq_disable(CAN_TypeDef *CANx) { NVIC_DisableIRQ(CAN2_TX_IRQn); NVIC_DisableIRQ(CAN2_RX0_IRQn); NVIC_DisableIRQ(CAN2_SCE_IRQn); - #ifdef CAN3 - } else if (CANx == CAN3) { - NVIC_DisableIRQ(CAN3_TX_IRQn); - NVIC_DisableIRQ(CAN3_RX0_IRQn); - NVIC_DisableIRQ(CAN3_SCE_IRQn); - #endif + } else if (CANx == CAN3) { + NVIC_DisableIRQ(CAN3_TX_IRQn); + NVIC_DisableIRQ(CAN3_RX0_IRQn); + NVIC_DisableIRQ(CAN3_SCE_IRQn); } else { } } -void llcan_irq_enable(CAN_TypeDef *CANx) { +void llcan_irq_enable(const CAN_TypeDef *CANx) { if (CANx == CAN1) { NVIC_EnableIRQ(CAN1_TX_IRQn); NVIC_EnableIRQ(CAN1_RX0_IRQn); @@ -103,12 +101,10 @@ void llcan_irq_enable(CAN_TypeDef *CANx) { NVIC_EnableIRQ(CAN2_TX_IRQn); NVIC_EnableIRQ(CAN2_RX0_IRQn); NVIC_EnableIRQ(CAN2_SCE_IRQn); - #ifdef CAN3 - } else if (CANx == CAN3) { - NVIC_EnableIRQ(CAN3_TX_IRQn); - NVIC_EnableIRQ(CAN3_RX0_IRQn); - NVIC_EnableIRQ(CAN3_SCE_IRQn); - #endif + } else if (CANx == CAN3) { + NVIC_EnableIRQ(CAN3_TX_IRQn); + NVIC_EnableIRQ(CAN3_RX0_IRQn); + NVIC_EnableIRQ(CAN3_SCE_IRQn); } else { } } @@ -140,7 +136,7 @@ bool llcan_init(CAN_TypeDef *CANx) { CANx->sFilterRegister[0].FR2 = 0U; CANx->sFilterRegister[14].FR1 = 0U; CANx->sFilterRegister[14].FR2 = 0U; - CANx->FA1R |= 1U | (1U << 14); + CANx->FA1R |= 1U | (1UL << 14); // Exit init mode, do not wait register_clear_bits(&(CANx->FMR), CAN_FMR_FINIT); diff --git a/panda/board/stm32fx/lldac.h b/panda/board/stm32fx/lldac.h deleted file mode 100644 index 6cd2f8ca2c..0000000000 --- a/panda/board/stm32fx/lldac.h +++ /dev/null @@ -1,16 +0,0 @@ -void dac_init(void) { - // No buffers required since we have an opamp - register_set(&(DAC->DHR12R1), 0U, 0xFFFU); - register_set(&(DAC->DHR12R2), 0U, 0xFFFU); - register_set(&(DAC->CR), DAC_CR_EN1 | DAC_CR_EN2, 0x3FFF3FFFU); -} - -void dac_set(int channel, uint32_t value) { - if (channel == 0) { - register_set(&(DAC->DHR12R1), value, 0xFFFU); - } else if (channel == 1) { - register_set(&(DAC->DHR12R2), value, 0xFFFU); - } else { - print("Failed to set DAC: invalid channel value: 0x"); puth(value); print("\n"); - } -} diff --git a/panda/board/stm32fx/lluart.h b/panda/board/stm32fx/lluart.h index 91c24dafca..ffe7e74da0 100644 --- a/panda/board/stm32fx/lluart.h +++ b/panda/board/stm32fx/lluart.h @@ -79,49 +79,14 @@ void uart_interrupt_handler(uart_ring *q) { } void USART2_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_debug); } -void USART3_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin2); } -void UART5_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin1); } // ***************************** Hardware setup ***************************** -#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) -#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100U) -#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) -#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) +#define DIV_(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) +#define DIVMANT_(_PCLK_, _BAUD_) (DIV_((_PCLK_), (_BAUD_)) / 100U) +#define DIVFRAQ_(_PCLK_, _BAUD_) ((((DIV_((_PCLK_), (_BAUD_)) - (DIVMANT_((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) +#define USART_BRR_(_PCLK_, _BAUD_) ((DIVMANT_((_PCLK_), (_BAUD_)) << 4) | (DIVFRAQ_((_PCLK_), (_BAUD_)) & 0x0FU)) void uart_set_baud(USART_TypeDef *u, unsigned int baud) { - u->BRR = __USART_BRR(APB1_FREQ*1000000U, baud); -} - -void uart_init(uart_ring *q, int baud) { - if(q->uart != NULL){ - // Register interrupts (max data rate: 115200 baud) - if (q->uart == USART2){ - REGISTER_INTERRUPT(USART2_IRQn, USART2_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_2) - } else if (q->uart == USART3){ - REGISTER_INTERRUPT(USART3_IRQn, USART3_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_3) - } else if (q->uart == UART5){ - REGISTER_INTERRUPT(UART5_IRQn, UART5_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_5) - } else { - // UART not used. Skip registering interrupts - } - - // Set baud and enable peripheral with TX and RX mode - uart_set_baud(q->uart, baud); - q->uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; - if ((q->uart == USART2) || (q->uart == USART3) || (q->uart == UART5)) { - q->uart->CR1 |= USART_CR1_RXNEIE; - } - - // Enable UART interrupts - if (q->uart == USART2){ - NVIC_EnableIRQ(USART2_IRQn); - } else if (q->uart == USART3){ - NVIC_EnableIRQ(USART3_IRQn); - } else if (q->uart == UART5){ - NVIC_EnableIRQ(UART5_IRQn); - } else { - // UART not used. Skip enabling interrupts - } - } + u->BRR = USART_BRR_(APB1_FREQ*1000000U, baud); } diff --git a/panda/board/stm32fx/llusb.h b/panda/board/stm32fx/llusb.h index ab34672aa4..20c980864b 100644 --- a/panda/board/stm32fx/llusb.h +++ b/panda/board/stm32fx/llusb.h @@ -1,20 +1,13 @@ -typedef struct -{ - __IO uint32_t HPRT; -} -USB_OTG_HostPortTypeDef; - USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; #define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) -#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE)) #define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) #define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) #define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) #define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) #define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) -#define USBD_FS_TRDT_VALUE 5U +#define USBD_FS_TRDT_VALUE 5UL #define USB_OTG_SPEED_FULL 3 @@ -49,7 +42,6 @@ void usb_init(void) { USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); // power up the PHY -#ifdef STM32F4 USBx->GCCFG = USB_OTG_GCCFG_PWRDWN; //USBx->GCCFG |= USB_OTG_GCCFG_VBDEN | USB_OTG_GCCFG_SDEN |USB_OTG_GCCFG_PDEN | USB_OTG_GCCFG_DCDEN; @@ -57,9 +49,6 @@ void usb_init(void) { /* B-peripheral session valid override enable*/ USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; -#else - USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS; -#endif // be a device, slowest timings //USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; diff --git a/panda/board/stm32fx/peripherals.h b/panda/board/stm32fx/peripherals.h index 5bdb8a056c..79ac3c6e4c 100644 --- a/panda/board/stm32fx/peripherals.h +++ b/panda/board/stm32fx/peripherals.h @@ -36,14 +36,9 @@ void common_init_gpio(void) { gpio_usb_init(); - // B8,B9: CAN 1 - #ifdef STM32F4 - set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1); - set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); - #else - set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); - set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); - #endif + // B8,B9: CAN 1 + set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1); + set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); } void flasher_peripherals_init(void) { @@ -71,14 +66,10 @@ void peripherals_init(void) { RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; RCC->APB1ENR |= RCC_APB1ENR_USART2EN; RCC->APB1ENR |= RCC_APB1ENR_USART3EN; - #ifndef PEDAL - RCC->APB1ENR |= RCC_APB1ENR_UART5EN; - #endif + RCC->APB1ENR |= RCC_APB1ENR_UART5EN; RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; - #ifdef CAN3 - RCC->APB1ENR |= RCC_APB1ENR_CAN3EN; - #endif + RCC->APB1ENR |= RCC_APB1ENR_CAN3EN; // Analog RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; diff --git a/panda/board/stm32fx/startup_stm32f205xx.s b/panda/board/stm32fx/startup_stm32f205xx.s deleted file mode 100644 index 7554efc4c1..0000000000 --- a/panda/board/stm32fx/startup_stm32f205xx.s +++ /dev/null @@ -1,511 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f205xx.s - * @author MCD Application Team - * @version V2.1.2 - * @date 29-June-2016 - * @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m3 - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - bl __initialize_hardware_early - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system initialization function.*/ - /*bl SystemInit */ -/* Call static constructors */ - /*bl __libc_init_array*/ -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - - -g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak CAN2_TX_IRQHandler - .thumb_set CAN2_TX_IRQHandler,Default_Handler - - .weak CAN2_RX0_IRQHandler - .thumb_set CAN2_RX0_IRQHandler,Default_Handler - - .weak CAN2_RX1_IRQHandler - .thumb_set CAN2_RX1_IRQHandler,Default_Handler - - .weak CAN2_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/stm32f2_flash.ld b/panda/board/stm32fx/stm32f2_flash.ld deleted file mode 100644 index bdc23bc8ce..0000000000 --- a/panda/board/stm32fx/stm32f2_flash.ld +++ /dev/null @@ -1,165 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32f4_flash.ld -** -** Abstract : Linker script for STM32F407VG Device with -** 1024KByte FLASH, 192KByte RAM -** -** Set heap size, stack size and stack location according -** to application requirements. -** -** Set memory bank area and size if external memory is used. -** -** Target : STMicroelectronics STM32 -** -** Environment : Atollic TrueSTUDIO(R) -** -** Distribution: The file is distributed "as is," without any warranty -** of any kind. -** -** (c)Copyright Atollic AB. -** You may use this file as-is or modify it according to the needs of your -** project. Distribution of this file (unmodified or modified) is not -** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the -** rights to distribute the assembled, compiled & linked contents of this -** file as part of an application binary file, provided that it is built -** using the Atollic TrueSTUDIO(R) toolchain. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -enter_bootloader_mode = 0x2001FFFC; -_estack = 0x2001FFFC; /* end of 128K RAM on AHB bus*/ -_app_start = 0x08004000; /* Reserve Sector 0(16K) for bootloader */ - -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - _exit = .; - } >FLASH - - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(.fini_array*)) - KEEP (*(SORT(.fini_array.*))) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = .; - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >RAM - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* MEMORY_bank1 section, code must be located here explicitly */ - /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ - .memory_b1_text : - { - *(.mb1text) /* .mb1text sections (code) */ - *(.mb1text*) /* .mb1text* sections (code) */ - *(.mb1rodata) /* read-only data (constants) */ - *(.mb1rodata*) - } >MEMORY_B1 - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/panda/board/stm32fx/stm32fx_config.h b/panda/board/stm32fx/stm32fx_config.h index 4d382e0e74..8b59da28f0 100644 --- a/panda/board/stm32fx/stm32fx_config.h +++ b/panda/board/stm32fx/stm32fx_config.h @@ -1,12 +1,7 @@ -#ifdef STM32F4 - #include "stm32fx/inc/stm32f4xx.h" - #include "stm32fx/inc/stm32f4xx_hal_gpio_ex.h" - #define MCU_IDCODE 0x463U -#else - #include "stm32fx/inc/stm32f2xx.h" - #include "stm32fx/inc/stm32f2xx_hal_gpio_ex.h" - #define MCU_IDCODE 0x411U -#endif +#include "stm32fx/inc/stm32f4xx.h" +#include "stm32fx/inc/stm32f4xx_hal_gpio_ex.h" +#define MCU_IDCODE 0x463U + // from the linker script #define APP_START_ADDRESS 0x8004000U @@ -28,9 +23,6 @@ #define TICK_TIMER_IRQ TIM1_BRK_TIM9_IRQn #define TICK_TIMER TIM9 -#define GMLAN_BITBANG_TIMER_IRQ TIM8_BRK_TIM12_IRQn -#define GMLAN_BITBANG_TIMER TIM12 - #define MICROSECOND_TIMER TIM2 #define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn @@ -45,11 +37,7 @@ #include "comms_definitions.h" #ifndef BOOTSTUB - #ifdef PEDAL - #include "pedal/main_declarations.h" - #else - #include "main_declarations.h" - #endif + #include "main_declarations.h" #else #include "bootstub_declarations.h" #endif @@ -69,12 +57,10 @@ #include "stm32fx/clock.h" #include "drivers/watchdog.h" -#if !defined(PEDAL) || defined(BOOTSTUB) - #include "drivers/spi.h" - #include "stm32fx/llspi.h" -#endif +#include "drivers/spi.h" +#include "stm32fx/llspi.h" -#if !defined(BOOTSTUB) && (!defined(PEDAL) || defined(PEDAL_USB)) +#if !defined(BOOTSTUB) #include "drivers/uart.h" #include "stm32fx/lluart.h" #endif @@ -89,13 +75,7 @@ #include "stm32fx/llbxcan.h" #endif -#if !defined(PEDAL) || defined(PEDAL_USB) || defined(BOOTSTUB) - #include "stm32fx/llusb.h" -#endif - -#ifdef PEDAL - #include "stm32fx/lldac.h" -#endif +#include "stm32fx/llusb.h" void early_gpio_float(void) { RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN; diff --git a/panda/board/stm32h7/board.h b/panda/board/stm32h7/board.h index d991e433b1..d293a54cfe 100644 --- a/panda/board/stm32h7/board.h +++ b/panda/board/stm32h7/board.h @@ -16,8 +16,8 @@ #include "drivers/clock_source.h" #include "boards/red.h" #include "boards/red_chiplet.h" -#include "boards/red_v2.h" #include "boards/tres.h" +#include "boards/cuatro.h" uint8_t get_board_id(void) { @@ -34,13 +34,22 @@ void detect_board_type(void) { hw_type = HW_TYPE_RED_PANDA; current_board = &board_red; } else if (board_id == 1U) { - hw_type = HW_TYPE_RED_PANDA_V2; - current_board = &board_red_v2; + // deprecated + //hw_type = HW_TYPE_RED_PANDA_V2; } else if (board_id == 2U) { hw_type = HW_TYPE_TRES; current_board = &board_tres; + } else if (board_id == 3U) { + hw_type = HW_TYPE_CUATRO; + current_board = &board_tres; } else { hw_type = HW_TYPE_UNKNOWN; print("Hardware type is UNKNOWN!\n"); } + + // TODO: detect this live +#ifdef STM32H723 + hw_type = HW_TYPE_CUATRO; + current_board = &board_cuatro; +#endif } diff --git a/panda/board/stm32h7/clock.h b/panda/board/stm32h7/clock.h index c5f93cd02e..7d65d080ec 100644 --- a/panda/board/stm32h7/clock.h +++ b/panda/board/stm32h7/clock.h @@ -18,12 +18,15 @@ PCLK1: 60MHz (for USART2,3,4,5,7,8) */ void clock_init(void) { - //Set power mode to direct SMPS power supply(depends on the board layout) + // Set power mode to direct SMPS power supply(depends on the board layout) +#ifndef STM32H723 register_set(&(PWR->CR3), PWR_CR3_SMPSEN, 0xFU); // powered only by SMPS - //Set VOS level (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) +#endif + // Set VOS level (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) register_set(&(PWR->D3CR), PWR_D3CR_VOS_1 | PWR_D3CR_VOS_0, 0xC000U); //VOS1, needed for 80Mhz CAN FD while ((PWR->CSR1 & PWR_CSR1_ACTVOSRDY) == 0); while ((PWR->CSR1 & PWR_CSR1_ACTVOS) != (PWR->D3CR & PWR_D3CR_VOS)); // check that VOS level was actually set + // Configure Flash ACR register LATENCY and WRHIGHFREQ (VOS0 range!) register_set(&(FLASH->ACR), FLASH_ACR_LATENCY_2WS | 0x20U, 0x3FU); // VOS2, AXI 100MHz-150MHz // enable external oscillator HSE diff --git a/panda/board/stm32h7/lladc.h b/panda/board/stm32h7/lladc.h index 0a52b78d37..01342a4d05 100644 --- a/panda/board/stm32h7/lladc.h +++ b/panda/board/stm32h7/lladc.h @@ -1,6 +1,3 @@ -// 5VOUT_S = ADC12_INP5 -// VOLT_S = ADC1_INP2 -#define ADCCHAN_VIN 2 void adc_init(void) { ADC1->CR &= ~(ADC_CR_DEEPPWD); //Reset deep-power-down mode @@ -18,17 +15,18 @@ void adc_init(void) { } uint16_t adc_get_raw(uint8_t channel) { + uint16_t res = 0U; ADC1->SQR1 &= ~(ADC_SQR1_L); ADC1->SQR1 = ((uint32_t) channel << 6U); ADC1->SMPR1 = (0x2U << (channel * 3U)); - ADC1->PCSEL_RES0 = (0x1U << channel); + ADC1->PCSEL_RES0 = (0x1UL << channel); ADC1->CFGR2 = (127U << ADC_CFGR2_OVSR_Pos) | (0x7U << ADC_CFGR2_OVSS_Pos) | ADC_CFGR2_ROVSE; ADC1->CR |= ADC_CR_ADSTART; while (!(ADC1->ISR & ADC_ISR_EOC)); - uint16_t res = ADC1->DR; + res = ADC1->DR; while (!(ADC1->ISR & ADC_ISR_EOS)); ADC1->ISR |= ADC_ISR_EOS; diff --git a/panda/board/stm32h7/lldac.h b/panda/board/stm32h7/lldac.h index 77e333e5c8..5726f62413 100644 --- a/panda/board/stm32h7/lldac.h +++ b/panda/board/stm32h7/lldac.h @@ -28,7 +28,7 @@ void dac_init(DAC_TypeDef *dac, uint8_t channel, bool dma) { // Set channel 1 value, in mV void dac_set(DAC_TypeDef *dac, uint8_t channel, uint32_t value) { - uint32_t raw_val = MAX(MIN(value * (1U << 8U) / 3300U, (1U << 8U)), 0U); + uint32_t raw_val = MAX(MIN(value * (1UL << 8U) / 3300U, (1UL << 8U)), 0U); switch(channel) { case 1: register_set(&dac->DHR8R1, raw_val, 0xFFU); diff --git a/panda/board/stm32h7/llfdcan.h b/panda/board/stm32h7/llfdcan.h index 5f13dfaa9c..4bb6d3d04e 100644 --- a/panda/board/stm32h7/llfdcan.h +++ b/panda/board/stm32h7/llfdcan.h @@ -112,10 +112,10 @@ bool llcan_set_speed(FDCAN_GlobalTypeDef *FDCANx, uint32_t speed, uint32_t data_ } // Set the nominal bit timing values - uint16_t tq = CAN_QUANTA(speed, prescaler); - uint8_t sp = CAN_SP_NOMINAL; - uint8_t seg1 = CAN_SEG1(tq, sp); - uint8_t seg2 = CAN_SEG2(tq, sp); + uint32_t tq = CAN_QUANTA(speed, prescaler); + uint32_t sp = CAN_SP_NOMINAL; + uint32_t seg1 = CAN_SEG1(tq, sp); + uint32_t seg2 = CAN_SEG2(tq, sp); uint8_t sjw = MIN(127U, seg2); FDCANx->NBTP = (((sjw & 0x7FU)-1U)<APB1LENR |= RCC_APB1LENR_TIM3EN; // fan pwm RCC->APB1LENR |= RCC_APB1LENR_TIM6EN; // interrupt timer RCC->APB1LENR |= RCC_APB1LENR_TIM7EN; // DMA trigger timer - RCC->APB1LENR |= RCC_APB1LENR_TIM12EN; // tick timer - RCC->APB1LENR |= RCC_APB1LENR_TIM13EN; // gmlan bitbang timer + RCC->APB2ENR |= RCC_APB2ENR_TIM8EN; // tick timer + RCC->APB1LENR |= RCC_APB1LENR_TIM12EN; // slow loop #ifdef PANDA_JUNGLE RCC->AHB3ENR |= RCC_AHB3ENR_SDMMC1EN; // SDMMC diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h index 880ee4559d..6f36a5aaf4 100644 --- a/panda/board/stm32h7/stm32h7_config.h +++ b/panda/board/stm32h7/stm32h7_config.h @@ -36,9 +36,6 @@ separate IRQs for RX and TX. #define TICK_TIMER_IRQ TIM8_BRK_TIM12_IRQn #define TICK_TIMER TIM12 -#define GMLAN_BITBANG_TIMER_IRQ TIM8_UP_TIM13_IRQn -#define GMLAN_BITBANG_TIMER TIM13 - #define MICROSECOND_TIMER TIM2 #define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn @@ -96,7 +93,7 @@ separate IRQs for RX and TX. void early_gpio_float(void) { RCC->AHB4ENR = RCC_AHB4ENR_GPIOAEN | RCC_AHB4ENR_GPIOBEN | RCC_AHB4ENR_GPIOCEN | RCC_AHB4ENR_GPIODEN | RCC_AHB4ENR_GPIOEEN | RCC_AHB4ENR_GPIOFEN | RCC_AHB4ENR_GPIOGEN | RCC_AHB4ENR_GPIOHEN; - GPIOA->MODER = 0xAB000000; GPIOB->MODER = 0; GPIOC->MODER = 0; GPIOD->MODER = 0; GPIOE->MODER = 0; GPIOF->MODER = 0; GPIOG->MODER = 0; GPIOH->MODER = 0; + GPIOA->MODER = 0xAB000000U; GPIOB->MODER = 0; GPIOC->MODER = 0; GPIOD->MODER = 0; GPIOE->MODER = 0; GPIOF->MODER = 0; GPIOG->MODER = 0; GPIOH->MODER = 0; GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; GPIOD->ODR = 0; GPIOE->ODR = 0; GPIOF->ODR = 0; GPIOG->ODR = 0; GPIOH->ODR = 0; GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; GPIOD->PUPDR = 0; GPIOE->PUPDR = 0; GPIOF->PUPDR = 0; GPIOG->PUPDR = 0; GPIOH->PUPDR = 0; } diff --git a/panda/board/utils.h b/panda/board/utils.h index 3ab6b30bc8..fd69db1bbf 100644 --- a/panda/board/utils.h +++ b/panda/board/utils.h @@ -23,6 +23,9 @@ }) #ifndef NULL +// this just provides a standard implementation of NULL +// in lieu of including libc in the panda build +// cppcheck-suppress [misra-c2012-21.1] #define NULL ((void*)0) #endif @@ -31,7 +34,7 @@ #define UNUSED(x) ((void)(x)) #endif -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) +#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * (!(pred) ? 1 : 0))])) // compute the time elapsed (in microseconds) from 2 counter samples // case where ts < ts_last is ok: overflow is properly re-casted into uint32_t diff --git a/panda/python/__init__.py b/panda/python/__init__.py index ee5ac8d966..acf6ea4834 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -28,6 +28,7 @@ logging.basicConfig(level=LOGLEVEL, format='%(message)s') CANPACKET_HEAD_SIZE = 0x6 DLC_TO_LEN = [0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64] LEN_TO_DLC = {length: dlc for (dlc, length) in enumerate(DLC_TO_LEN)} +PANDA_BUS_CNT = 4 def calculate_checksum(data): @@ -111,6 +112,7 @@ class ALTERNATIVE_EXPERIENCE: DISABLE_DISENGAGE_ON_GAS = 1 DISABLE_STOCK_AEB = 2 RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX = 8 + ALLOW_AEB = 16 class Panda: @@ -165,24 +167,25 @@ class Panda: HW_TYPE_RED_PANDA = b'\x07' HW_TYPE_RED_PANDA_V2 = b'\x08' HW_TYPE_TRES = b'\x09' + HW_TYPE_CUATRO = b'\x0a' CAN_PACKET_VERSION = 4 - HEALTH_PACKET_VERSION = 14 + HEALTH_PACKET_VERSION = 15 CAN_HEALTH_PACKET_VERSION = 5 - HEALTH_STRUCT = struct.Struct(" McuType: hw_type = self.get_type() - if hw_type in Panda.F2_DEVICES: - return McuType.F2 - elif hw_type in Panda.F4_DEVICES: + if hw_type in Panda.F4_DEVICES: return McuType.F4 elif hw_type in Panda.H7_DEVICES: return McuType.H7 @@ -879,63 +886,6 @@ class Panda: """ self._handle.controlWrite(Panda.REQUEST_OUT, 0xf2, port_number, 0, b'') - # ******************* kline ******************* - - # pulse low for wakeup - def kline_wakeup(self, k=True, l=True): - assert k or l, "must specify k-line, l-line, or both" - logging.debug("kline wakeup...") - self._handle.controlWrite(Panda.REQUEST_OUT, 0xf0, 2 if k and l else int(l), 0, b'') - logging.debug("kline wakeup done") - - def kline_5baud(self, addr, k=True, l=True): - assert k or l, "must specify k-line, l-line, or both" - logging.debug("kline 5 baud...") - self._handle.controlWrite(Panda.REQUEST_OUT, 0xf4, 2 if k and l else int(l), addr, b'') - logging.debug("kline 5 baud done") - - def kline_drain(self, bus=2): - # drain buffer - bret = bytearray() - while True: - ret = self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, 0x40) - if len(ret) == 0: - break - logging.debug(f"kline drain: 0x{ret.hex()}") - bret += ret - return bytes(bret) - - def kline_ll_recv(self, cnt, bus=2): - echo = bytearray() - while len(echo) != cnt: - ret = self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt - len(echo)) - if len(ret) > 0: - logging.debug(f"kline recv: 0x{ret.hex()}") - echo += ret - return bytes(echo) - - def kline_send(self, x, bus=2, checksum=True): - self.kline_drain(bus=bus) - if checksum: - x += bytes([sum(x) % 0x100]) - for i in range(0, len(x), 0xf): - ts = x[i:i + 0xf] - logging.debug(f"kline send: 0x{ts.hex()}") - self._handle.bulkWrite(2, bytes([bus]) + ts) - echo = self.kline_ll_recv(len(ts), bus=bus) - if echo != ts: - logging.error(f"**** ECHO ERROR {i} ****") - logging.error(f"0x{echo.hex()}") - logging.error(f"0x{ts.hex()}") - assert echo == ts - - def kline_recv(self, bus=2, header_len=4): - # read header (last byte is length) - msg = self.kline_ll_recv(header_len, bus=bus) - # read data (add one byte to length for checksum) - msg += self.kline_ll_recv(msg[-1]+1, bus=bus) - return msg - def send_heartbeat(self, engaged=True): self._handle.controlWrite(Panda.REQUEST_OUT, 0xf3, engaged, 0, b'') @@ -977,10 +927,6 @@ class Panda: a = struct.unpack("H", dat) return a[0] - # ****************** Phone ***************** - def set_phone_power(self, enabled): - self._handle.controlWrite(Panda.REQUEST_OUT, 0xb3, int(enabled), 0, b'') - # ****************** Siren ***************** def set_siren(self, enabled): self._handle.controlWrite(Panda.REQUEST_OUT, 0xf6, int(enabled), 0, b'') diff --git a/panda/python/constants.py b/panda/python/constants.py index 8078da3e62..fede52424c 100644 --- a/panda/python/constants.py +++ b/panda/python/constants.py @@ -24,7 +24,11 @@ class McuConfig(NamedTuple): # assume bootstub is in sector 0 return self.bootstub_address + sum(self.sector_sizes[:i]) -Fx = ( +F4Config = McuConfig( + "STM32F4", + 0x463, + [0x4000 for _ in range(4)] + [0x10000] + [0x20000 for _ in range(11)], + 16, 0x1FFF7A10, 0x800, 0x1FFF79C0, @@ -33,8 +37,6 @@ Fx = ( 0x8000000, "bootstub.panda.bin", ) -F2Config = McuConfig("STM32F2", 0x411, [0x4000 for _ in range(4)] + [0x10000] + [0x20000 for _ in range(7)], 12, *Fx) -F4Config = McuConfig("STM32F4", 0x463, [0x4000 for _ in range(4)] + [0x10000] + [0x20000 for _ in range(11)], 16, *Fx) H7Config = McuConfig( "STM32H7", @@ -53,7 +55,6 @@ H7Config = McuConfig( @enum.unique class McuType(enum.Enum): - F2 = F2Config F4 = F4Config H7 = H7Config diff --git a/panda/python/dfu.py b/panda/python/dfu.py index 661f9e8f1d..01ff037f84 100644 --- a/panda/python/dfu.py +++ b/panda/python/dfu.py @@ -72,7 +72,7 @@ class PandaDFU: return None, handle @staticmethod - def list() -> List[str]: # noqa: A003 + def list() -> List[str]: ret = PandaDFU.usb_list() ret += PandaDFU.spi_list() return list(set(ret)) diff --git a/panda/python/spi.py b/panda/python/spi.py index 699431bf0c..48dc84d49e 100644 --- a/panda/python/spi.py +++ b/panda/python/spi.py @@ -13,7 +13,6 @@ from typing import Callable, List, Optional from .base import BaseHandle, BaseSTBootloaderHandle, TIMEOUT from .constants import McuType, MCU_TYPE_BY_IDCODE, USBPACKET_MAX_SIZE -from .utils import crc8_pedal try: import spidev @@ -35,6 +34,20 @@ XFER_SIZE = 0x40*31 DEV_PATH = "/dev/spidev0.0" +def crc8(data): + crc = 0xFF # standard init value + poly = 0xD5 # standard crc8: x8+x7+x6+x4+x2+1 + size = len(data) + for i in range(size - 1, -1, -1): + crc ^= data[i] + for _ in range(8): + if ((crc & 0x80) != 0): + crc = ((crc << 1) ^ poly) & 0xFF + else: + crc <<= 1 + return crc + + class PandaSpiException(Exception): pass @@ -248,7 +261,7 @@ class PandaSpiHandle(BaseHandle): # get response dat = spi.readbytes(rlen + 1) resp = dat[:-1] - calculated_crc = crc8_pedal(bytes(version_bytes + resp)) + calculated_crc = crc8(bytes(version_bytes + resp)) if calculated_crc != dat[-1]: raise PandaSpiBadChecksum return bytes(resp) diff --git a/panda/python/utils.py b/panda/python/utils.py deleted file mode 100644 index f91da64130..0000000000 --- a/panda/python/utils.py +++ /dev/null @@ -1,12 +0,0 @@ -def crc8_pedal(data): - crc = 0xFF # standard init value - poly = 0xD5 # standard crc8: x8+x7+x6+x4+x2+1 - size = len(data) - for i in range(size - 1, -1, -1): - crc ^= data[i] - for _ in range(8): - if ((crc & 0x80) != 0): - crc = ((crc << 1) ^ poly) & 0xFF - else: - crc <<= 1 - return crc diff --git a/pyproject.toml b/pyproject.toml index 38c3337c6f..51396ca39b 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,7 +1,8 @@ [tool.pytest.ini_options] minversion = "6.0" -addopts = "--ignore=openpilot/ --ignore=cereal/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ -Werror --strict-config --strict-markers --durations=10 -n auto --dist=loadgroup" +addopts = "--ignore=openpilot/ --ignore=cereal/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ --ignore=teleoprtc_repo/ -Werror --strict-config --strict-markers --durations=10 -n auto --dist=loadgroup" cpp_files = "test_*" +cpp_harness = "selfdrive/test/cpp_harness.py" python_files = "test_*.py" #timeout = "30" # you get this long by default markers = [ @@ -16,13 +17,17 @@ testpaths = [ "selfdrive/controls", "selfdrive/locationd", "selfdrive/monitoring", + "selfdrive/navd/tests", "selfdrive/thermald", "selfdrive/test/longitudinal_maneuvers", + "selfdrive/test/process_replay/test_fuzzy.py", + "system/camerad", "system/hardware/tici", "system/loggerd", "system/proclogd", "system/tests", "system/ubloxd", + "system/webrtc", "tools/lib/tests", "tools/replay", "tools/cabana" @@ -42,6 +47,8 @@ exclude = [ "rednose_repo/", "tinygrad/", "tinygrad_repo/", + "teleoprtc/", + "teleoprtc_repo/", "third_party/", ] @@ -70,75 +77,69 @@ documentation = "https://docs.comma.ai" [tool.poetry.dependencies] python = "~3.11" -atomicwrites = "*" aiohttp = "*" aiortc = "*" casadi = "==3.6.3" cffi = "*" -control = "*" crcmod = "*" -cryptography = "*" Cython = "*" future-fstrings = "*" # for acados -hexdump = "*" -Jinja2 = "*" json-rpc = "*" libusb1 = "*" numpy = "*" onnx = ">=1.14.0" -onnxruntime = { version = ">=1.15.1", platform = "linux", markers = "platform_machine == 'aarch64'" } -onnxruntime-gpu = { version = ">=1.15.1", platform = "linux", markers = "platform_machine == 'x86_64'" } +onnxruntime = { version = ">=1.16.3", platform = "linux", markers = "platform_machine == 'aarch64'" } +onnxruntime-gpu = { version = ">=1.16.3", platform = "linux", markers = "platform_machine == 'x86_64'" } psutil = "*" pyaudio = "*" pycapnp = "*" pycryptodome = "*" -pycurl = "*" -pydub = "*" PyJWT = "*" -pyopencl = "*" pyserial = "*" -PyYAML = "*" pyzmq = "*" requests = "*" scons = "*" -sentry-sdk = "==1.28.1" # needs to be updated with AGNOS -setproctitle = "*" +sentry-sdk = "*" smbus2 = "*" sounddevice = "*" spidev = { version = "*", platform = "linux" } sympy = "*" -timezonefinder = "*" -tqdm = "*" websocket_client = "*" -polyline = "*" -sconscontrib = {git = "https://github.com/SCons/scons-contrib.git"} +# these should be removed +markdown-it-py = "*" +timezonefinder = "*" +setproctitle = "*" [tool.poetry.group.dev.dependencies] av = "*" azure-identity = "*" azure-storage-blob = "*" breathe = "*" +control = "*" coverage = "*" dictdiffer = "*" ft4222 = "*" +flaky = "*" hypothesis = "~6.47" inputs = "*" +Jinja2 = "*" lru-dict = "*" -markdown-it-py = "*" matplotlib = "*" -metadrive-simulator = { git = "https://github.com/metadriverse/metadrive.git", rev ="72e842cd1d025bf676e4af8797a01e4aa282109f", markers = "platform_machine != 'aarch64'" } # no linux/aarch64 wheels for certain dependencies +metadrive-simulator = { version = "0.4.2.3", markers = "platform_machine != 'aarch64'" } # no linux/aarch64 wheels for certain dependencies mpld3 = "*" mypy = "*" myst-parser = "*" natsort = "*" opencv-python-headless = "*" -pandas = "*" parameterized = "^0.8" pprofile = "*" +polyline = "*" pre-commit = "*" +pyautogui = "*" +pyopencl = "==2023.1.4" # 2024.1 is broken on arm64 pygame = "*" -pympler = "*" +pywinctl = "*" pyprof2calltree = "*" pytest = "*" pytest-cov = "*" @@ -146,38 +147,28 @@ pytest-cpp = "*" pytest-subtests = "*" pytest-xdist = "*" pytest-timeout = "*" -pytest-timeouts = "*" -pytest-random-order = "*" +pytest-randomly = "*" ruff = "*" -scipy = "*" sphinx = "*" sphinx-rtd-theme = "*" sphinx-sitemap = "*" tabulate = "*" tenacity = "*" -types-atomicwrites = "*" -types-pycurl = "*" -types-PyYAML = "*" types-requests = "*" types-tabulate = "*" +tqdm = "*" # this is only pinned since 5.15.11 is broken pyqt5 = { version = "==5.15.2", markers = "platform_machine == 'x86_64'" } # no aarch64 wheels for macOS/linux -[tool.poetry.group.carla] -optional = true - -[tool.poetry.group.carla.dependencies] -carla = { url = "https://github.com/commaai/carla/releases/download/3.11.4/carla-0.9.14-cp311-cp311-linux_x86_64.whl", platform = "linux", markers = "platform_machine == 'x86_64'" } - [build-system] requires = ["poetry-core"] build-backend = "poetry.core.masonry.api" # https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml [tool.ruff] -select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF008", "RUF100", "A", "B", "TID251"] -ignore = ["W292", "E741", "E402", "C408", "ISC003", "B027", "B024"] +lint.select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF008", "RUF100", "A", "B", "TID251"] +lint.ignore = ["E741", "E402", "C408", "ISC003", "B027", "B024"] line-length = 160 target-version="py311" exclude = [ @@ -185,10 +176,12 @@ exclude = [ "opendbc", "rednose_repo", "tinygrad_repo", + "teleoprtc", + "teleoprtc_repo", "third_party", ] -flake8-implicit-str-concat.allow-multiline=false -[tool.ruff.flake8-tidy-imports.banned-api] +lint.flake8-implicit-str-concat.allow-multiline=false +[tool.ruff.lint.flake8-tidy-imports.banned-api] "selfdrive".msg = "Use openpilot.selfdrive" "common".msg = "Use openpilot.common" "system".msg = "Use openpilot.system" @@ -196,4 +189,4 @@ flake8-implicit-str-concat.allow-multiline=false "tools".msg = "Use openpilot.tools" [tool.coverage.run] -concurrency = ["multiprocessing", "thread"] \ No newline at end of file +concurrency = ["multiprocessing", "thread"] diff --git a/rednose/SConscript b/rednose/SConscript index 398b4b473a..52e36e06f4 100644 --- a/rednose/SConscript +++ b/rednose/SConscript @@ -1,45 +1,17 @@ -Import('env', 'envCython', 'arch', 'rednose_config', 'common') +Import('env', 'envCython', 'common') -generated_folder = rednose_config['generated_folder'] - -templates = Glob('#rednose/templates/*') - -sympy_helpers = "#rednose/helpers/sympy_helpers.py" -ekf_sym = "#rednose/helpers/ekf_sym.py" -ekf_sym_pyx = "#rednose/helpers/ekf_sym_pyx.pyx" -ekf_sym_cc = env.Object("#rednose/helpers/ekf_sym.cc") -common_ekf = "#rednose/helpers/common_ekf.cc" - -found = {} -for target, (command, *args) in rednose_config['to_build'].items(): - if File(command).exists(): - found[target] = (command, *args) - -lib_target = [common_ekf] -for target, (command, combined_lib, extra_generated, deps) in found.items(): - target_files = File([f'{generated_folder}/{target}.cpp', f'{generated_folder}/{target}.h']) - extra_generated = [File(f'{generated_folder}/{x}') for x in extra_generated] - command_file = File(command) - - env.Command(target_files + extra_generated, - [templates, command_file, sympy_helpers, ekf_sym] + deps, - command_file.get_abspath() + " " + target + " " + Dir(generated_folder).get_abspath()) - - if combined_lib: - lib_target.append(target_files[0]) - else: - env.SharedLibrary(f'{generated_folder}/' + target, [target_files[0], common_ekf]) - -libkf = env.SharedLibrary(f'{generated_folder}/libkf', lib_target) - -lenv = envCython.Clone() -lenv["LINKFLAGS"] += [libkf[0].get_labspath()] - -# for SWAGLOG support +cc_sources = [ + "helpers/ekf_load.cc", + "helpers/ekf_sym.cc", +] +libs = ["dl"] if common != "": - lenv["LIBS"] = ['zmq', common] + lenv["LIBS"] + # for SWAGLOG support + libs += [common, 'zmq'] -ekf_sym_so = lenv.Program('#rednose/helpers/ekf_sym_pyx.so', [ekf_sym_pyx, ekf_sym_cc, common_ekf]) -lenv.Depends(ekf_sym_so, libkf) +ekf_objects = env.SharedObject(cc_sources) +rednose = env.Library("helpers/ekf_sym", ekf_objects, LIBS=libs) +rednose_python = envCython.Program("helpers/ekf_sym_pyx.so", ["helpers/ekf_sym_pyx.pyx", ekf_objects], + LIBS=libs + envCython["LIBS"]) -Export('libkf') +Export('rednose', 'rednose_python') diff --git a/rednose/helpers/__init__.py b/rednose/helpers/__init__.py index 12cce34815..b2beede2b8 100644 --- a/rednose/helpers/__init__.py +++ b/rednose/helpers/__init__.py @@ -13,11 +13,9 @@ def write_code(folder, name, code, header): open(os.path.join(folder, f"{name}.h"), 'w', encoding='utf-8').write(header) -def load_code(folder, name, lib_name=None): - if lib_name is None: - lib_name = name +def load_code(folder, name): shared_ext = "dylib" if platform.system() == "Darwin" else "so" - shared_fn = os.path.join(folder, f"lib{lib_name}.{shared_ext}") + shared_fn = os.path.join(folder, f"lib{name}.{shared_ext}") header_fn = os.path.join(folder, f"{name}.h") with open(header_fn, encoding='utf-8') as f: diff --git a/rednose/helpers/common_ekf.cc b/rednose/helpers/common_ekf.cc deleted file mode 100644 index 1e63902508..0000000000 --- a/rednose/helpers/common_ekf.cc +++ /dev/null @@ -1,19 +0,0 @@ -#include "common_ekf.h" - -std::vector& get_ekfs() { - static std::vector vec; - return vec; -} - -void ekf_register(const EKF* ekf) { - get_ekfs().push_back(ekf); -} - -const EKF* ekf_lookup(const std::string& ekf_name) { - for (const auto& ekfi : get_ekfs()) { - if (ekf_name == ekfi->name) { - return ekfi; - } - } - return NULL; -} diff --git a/rednose/helpers/common_ekf.h b/rednose/helpers/ekf.h similarity index 85% rename from rednose/helpers/common_ekf.h rename to rednose/helpers/ekf.h index 5dfdd448b6..2afe6dd2b6 100644 --- a/rednose/helpers/common_ekf.h +++ b/rednose/helpers/ekf.h @@ -32,12 +32,11 @@ struct EKF { std::unordered_map extra_routines = {}; }; -std::vector& get_ekfs(); -const EKF* ekf_lookup(const std::string& ekf_name); - -void ekf_register(const EKF* ekf); - -#define ekf_init(ekf) \ +#define ekf_lib_init(ekf) \ +extern "C" void* ekf_get() { \ + return (void*) &ekf; \ +} \ +extern void __attribute__((weak)) ekf_register(const EKF* ptr); \ static void __attribute__((constructor)) do_ekf_init_ ## ekf(void) { \ - ekf_register(&ekf); \ + if (ekf_register) ekf_register(&ekf); \ } diff --git a/rednose/helpers/ekf_load.cc b/rednose/helpers/ekf_load.cc new file mode 100644 index 0000000000..882b0b4a61 --- /dev/null +++ b/rednose/helpers/ekf_load.cc @@ -0,0 +1,39 @@ +#include "ekf_load.h" +#include + +std::vector& ekf_get_all() { + static std::vector vec; + return vec; +} + +void ekf_register(const EKF* ekf) { + ekf_get_all().push_back(ekf); +} + +const EKF* ekf_lookup(const std::string& ekf_name) { + for (const auto& ekfi : ekf_get_all()) { + if (ekf_name == ekfi->name) { + return ekfi; + } + } + return NULL; +} + +void ekf_load_and_register(const std::string& ekf_directory, const std::string& ekf_name) { + if (ekf_lookup(ekf_name)) { + return; + } + +#ifdef __APPLE__ + std::string dylib_ext = ".dylib"; +#else + std::string dylib_ext = ".so"; +#endif + std::string ekf_path = ekf_directory + "/lib" + ekf_name + dylib_ext; + void* handle = dlopen(ekf_path.c_str(), RTLD_NOW); + assert(handle); + void* (*ekf_get)() = (void*(*)())dlsym(handle, "ekf_get"); + assert(ekf_get != NULL); + const EKF* ekf = (const EKF*)ekf_get(); + ekf_register(ekf); +} diff --git a/rednose/helpers/ekf_load.h b/rednose/helpers/ekf_load.h new file mode 100644 index 0000000000..89180b8028 --- /dev/null +++ b/rednose/helpers/ekf_load.h @@ -0,0 +1,9 @@ +#include +#include + +#include "ekf.h" + +std::vector& ekf_get_all(); +const EKF* ekf_lookup(const std::string& ekf_name); +void ekf_register(const EKF* ekf); +void ekf_load_and_register(const std::string& ekf_directory, const std::string& ekf_name); diff --git a/rednose/helpers/ekf_sym.cc b/rednose/helpers/ekf_sym.cc index cf3c88f12a..38d419d07f 100644 --- a/rednose/helpers/ekf_sym.cc +++ b/rednose/helpers/ekf_sym.cc @@ -9,7 +9,6 @@ EKFSym::EKFSym(std::string name, Map Q, Map x_initial, Map< std::vector quaternion_idxs, std::vector global_vars, double max_rewind_age) { // TODO: add logger - this->ekf = ekf_lookup(name); assert(this->ekf); diff --git a/rednose/helpers/ekf_sym.h b/rednose/helpers/ekf_sym.h index 86d6ca1938..b83d7f3a12 100644 --- a/rednose/helpers/ekf_sym.h +++ b/rednose/helpers/ekf_sym.h @@ -12,7 +12,8 @@ #include -#include "common_ekf.h" +#include "ekf.h" +#include "ekf_load.h" #define REWIND_TO_KEEP 512 diff --git a/rednose/helpers/ekf_sym.py b/rednose/helpers/ekf_sym.py index de68991a93..8f0425cb00 100644 --- a/rednose/helpers/ekf_sym.py +++ b/rednose/helpers/ekf_sym.py @@ -116,7 +116,7 @@ def gen_code(folder, name, f_sym, dt_sym, x_sym, obs_eqs, dim_x, dim_err, eskf_p sympy_header, code = sympy_into_c(sympy_functions, global_vars) header = "#pragma once\n" - header += "#include \"rednose/helpers/common_ekf.h\"\n" + header += "#include \"rednose/helpers/ekf.h\"\n" header += "extern \"C\" {\n" pre_code = f"#include \"{name}.h\"\n" @@ -200,7 +200,7 @@ def gen_code(folder, name, f_sym, dt_sym, x_sym, obs_eqs, dim_x, dim_err, eskf_p post_code += f" {{ \"{f}\", {name}_{f} }},\n" post_code += " },\n" post_code += "};\n\n" - post_code += f"ekf_init({name});\n" + post_code += f"ekf_lib_init({name})\n" # merge code blocks header += "}" @@ -252,7 +252,7 @@ class EKF_sym(): self.rewind_obscache = [] self.init_state(x_initial, P_initial, None) - ffi, lib = load_code(folder, name, "kf") + ffi, lib = load_code(folder, name) kinds, self.feature_track_kinds = [], [] for func in dir(lib): if func[:len(name) + 3] == f'{name}_h_': diff --git a/rednose/helpers/ekf_sym_pyx.pyx b/rednose/helpers/ekf_sym_pyx.pyx index e7461285ab..f552ea7354 100644 --- a/rednose/helpers/ekf_sym_pyx.pyx +++ b/rednose/helpers/ekf_sym_pyx.pyx @@ -11,12 +11,16 @@ cimport numpy as np import numpy as np + cdef extern from "" namespace "std" nogil: cdef cppclass optional[T]: ctypedef T value_type bool has_value() T& value() +cdef extern from "rednose/helpers/ekf_load.h": + cdef void ekf_load_and_register(string directory, string name) + cdef extern from "rednose/helpers/ekf_sym.h" namespace "EKFS": cdef cppclass MapVectorXd "Eigen::Map": MapVectorXd(double*, int) @@ -85,6 +89,7 @@ cdef class EKF_sym_pyx: int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # TODO logger + ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) diff --git a/rednose/helpers/feature_handler.py b/rednose/helpers/feature_handler.py deleted file mode 100755 index 165c9a4d0c..0000000000 --- a/rednose/helpers/feature_handler.py +++ /dev/null @@ -1,160 +0,0 @@ -#!/usr/bin/env python3 - -import os -import sys - -import numpy as np - -from rednose.helpers import TEMPLATE_DIR, load_code, write_code -from rednose.helpers.sympy_helpers import quat_matrix_l, rot_matrix - - -def sane(track): - img_pos = track[1:, 2:4] - diffs_x = abs(img_pos[1:, 0] - img_pos[:-1, 0]) - diffs_y = abs(img_pos[1:, 1] - img_pos[:-1, 1]) - for i in range(1, len(diffs_x)): - if ((diffs_x[i] > 0.05 or diffs_x[i - 1] > 0.05) and - (diffs_x[i] > 2 * diffs_x[i - 1] or - diffs_x[i] < .5 * diffs_x[i - 1])) or \ - ((diffs_y[i] > 0.05 or diffs_y[i - 1] > 0.05) and - (diffs_y[i] > 2 * diffs_y[i - 1] or - diffs_y[i] < .5 * diffs_y[i - 1])): - return False - return True - - -class FeatureHandler(): - name = 'feature_handler' - - @staticmethod - def generate_code(generated_dir, K=5): - # Wrap c code for slow matching - c_header = "\nvoid merge_features(double *tracks, double *features, long long *empty_idxs);" - - c_code = "#include \n" - c_code += "#include \n" - c_code += "#define K %d\n" % K - c_code += "extern \"C\" {\n" - c_code += "\n" + open(os.path.join(TEMPLATE_DIR, "feature_handler.c"), encoding='utf-8').read() - c_code += "\n}\n" - - filename = f"{FeatureHandler.name}_{K}" - write_code(generated_dir, filename, c_code, c_header) - - def __init__(self, generated_dir, K=5): - self.MAX_TRACKS = 6000 - self.K = K - - # Array of tracks, each track has K 5D features preceded - # by 5 params that inidicate [f_idx, last_idx, updated, complete, valid] - # f_idx: idx of current last feature in track - # idx of of last feature in frame - # bool for whether this track has been update - # bool for whether this track is complete - # bool for whether this track is valid - self.tracks = np.zeros((self.MAX_TRACKS, K + 1, 5)) - self.tracks[:] = np.nan - - name = f"{FeatureHandler.name}_{K}" - ffi, lib = load_code(generated_dir, name) - - def merge_features_c(tracks, features, empty_idxs): - lib.merge_features(ffi.cast("double *", tracks.ctypes.data), - ffi.cast("double *", features.ctypes.data), - ffi.cast("long long *", empty_idxs.ctypes.data)) - - # self.merge_features = self.merge_features_python - self.merge_features = merge_features_c - - def reset(self): - self.tracks[:] = np.nan - - def merge_features_python(self, tracks, features, empty_idxs): - empty_idx = 0 - for f in features: - match_idx = int(f[4]) - if tracks[match_idx, 0, 1] == match_idx and tracks[match_idx, 0, 2] == 0: - tracks[match_idx, 0, 0] += 1 - tracks[match_idx, 0, 1] = f[1] - tracks[match_idx, 0, 2] = 1 - tracks[match_idx, int(tracks[match_idx, 0, 0])] = f - if tracks[match_idx, 0, 0] == self.K: - tracks[match_idx, 0, 3] = 1 - if sane(tracks[match_idx]): - tracks[match_idx, 0, 4] = 1 - else: - if empty_idx == len(empty_idxs): - print('need more empty space') - continue - tracks[empty_idxs[empty_idx], 0, 0] = 1 - tracks[empty_idxs[empty_idx], 0, 1] = f[1] - tracks[empty_idxs[empty_idx], 0, 2] = 1 - tracks[empty_idxs[empty_idx], 1] = f - empty_idx += 1 - - def update_tracks(self, features): - last_idxs = np.copy(self.tracks[:, 0, 1]) - real = np.isfinite(last_idxs) - self.tracks[last_idxs[real].astype(int)] = self.tracks[real] - - mask = np.ones(self.MAX_TRACKS, bool) - mask[last_idxs[real].astype(int)] = 0 - empty_idxs = np.arange(self.MAX_TRACKS)[mask] - - self.tracks[empty_idxs] = np.nan - self.tracks[:, 0, 2] = 0 - self.merge_features(self.tracks, features, empty_idxs) - - def handle_features(self, features): - self.update_tracks(features) - valid_idxs = self.tracks[:, 0, 4] == 1 - complete_idxs = self.tracks[:, 0, 3] == 1 - stale_idxs = self.tracks[:, 0, 2] == 0 - valid_tracks = self.tracks[valid_idxs] - self.tracks[complete_idxs] = np.nan - self.tracks[stale_idxs] = np.nan - return valid_tracks[:, 1:, :4].reshape((len(valid_tracks), self.K * 4)) - - -def generate_orient_error_jac(K): - import sympy as sp - from rednose.helpers.sympy_helpers import quat_rotate - - x_sym = sp.MatrixSymbol('abr', 3, 1) - dtheta = sp.MatrixSymbol('dtheta', 3, 1) - delta_quat = sp.Matrix(np.ones(4)) - delta_quat[1:, :] = sp.Matrix(0.5 * dtheta[0:3, :]) - poses_sym = sp.MatrixSymbol('poses', 7 * K, 1) - img_pos_sym = sp.MatrixSymbol('img_positions', 2 * K, 1) - alpha, beta, rho = x_sym - to_c = sp.Matrix(rot_matrix(-np.pi / 2, -np.pi / 2, 0)) - pos_0 = sp.Matrix(np.array(poses_sym[K * 7 - 7:K * 7 - 4])[:, 0]) - q = quat_matrix_l(poses_sym[K * 7 - 4:K * 7]) * delta_quat - quat_rot = quat_rotate(*q) - rot_g_to_0 = to_c * quat_rot.T - rows = [] - for i in range(K): - pos_i = sp.Matrix(np.array(poses_sym[i * 7:i * 7 + 3])[:, 0]) - q = quat_matrix_l(poses_sym[7 * i + 3:7 * i + 7]) * delta_quat - quat_rot = quat_rotate(*q) - rot_g_to_i = to_c * quat_rot.T - rot_0_to_i = rot_g_to_i * (rot_g_to_0.T) - trans_0_to_i = rot_g_to_i * (pos_0 - pos_i) - funct_vec = rot_0_to_i * sp.Matrix([alpha, beta, 1]) + rho * trans_0_to_i - h1, h2, h3 = funct_vec - rows.append(h1 / h3 - img_pos_sym[i * 2 + 0]) - rows.append(h2 / h3 - img_pos_sym[i * 2 + 1]) - img_pos_residual_sym = sp.Matrix(rows) - - # sympy into c - sympy_functions = [] - sympy_functions.append(('orient_error_jac', img_pos_residual_sym.jacobian(dtheta), [x_sym, poses_sym, img_pos_sym, dtheta])) - - return sympy_functions - - -if __name__ == "__main__": - K = int(sys.argv[1].split("_")[-1]) - generated_dir = sys.argv[2] - FeatureHandler.generate_code(generated_dir, K=K) diff --git a/rednose/helpers/lst_sq_computer.py b/rednose/helpers/lst_sq_computer.py deleted file mode 100755 index 3c74eaac5d..0000000000 --- a/rednose/helpers/lst_sq_computer.py +++ /dev/null @@ -1,175 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys - -import numpy as np -import sympy as sp - -from rednose.helpers import TEMPLATE_DIR, load_code, write_code -from rednose.helpers.sympy_helpers import quat_rotate, sympy_into_c, rot_matrix, rotations_from_quats - - -def generate_residual(K): - x_sym = sp.MatrixSymbol('abr', 3, 1) - poses_sym = sp.MatrixSymbol('poses', 7 * K, 1) - img_pos_sym = sp.MatrixSymbol('img_positions', 2 * K, 1) - alpha, beta, rho = x_sym - to_c = sp.Matrix(rot_matrix(-np.pi / 2, -np.pi / 2, 0)) - pos_0 = sp.Matrix(np.array(poses_sym[K * 7 - 7:K * 7 - 4])[:, 0]) - q = poses_sym[K * 7 - 4:K * 7] - quat_rot = quat_rotate(*q) - rot_g_to_0 = to_c * quat_rot.T - rows = [] - - for i in range(K): - pos_i = sp.Matrix(np.array(poses_sym[i * 7:i * 7 + 3])[:, 0]) - q = poses_sym[7 * i + 3:7 * i + 7] - quat_rot = quat_rotate(*q) - rot_g_to_i = to_c * quat_rot.T - rot_0_to_i = rot_g_to_i * rot_g_to_0.T - trans_0_to_i = rot_g_to_i * (pos_0 - pos_i) - funct_vec = rot_0_to_i * sp.Matrix([alpha, beta, 1]) + rho * trans_0_to_i - h1, h2, h3 = funct_vec - rows.append(h1 / h3 - img_pos_sym[i * 2 + 0]) - rows.append(h2 / h3 - img_pos_sym[i * 2 + 1]) - img_pos_residual_sym = sp.Matrix(rows) - - # sympy into c - sympy_functions = [] - sympy_functions.append(('res_fun', img_pos_residual_sym, [x_sym, poses_sym, img_pos_sym])) - sympy_functions.append(('jac_fun', img_pos_residual_sym.jacobian(x_sym), [x_sym, poses_sym, img_pos_sym])) - - return sympy_functions - - -class LstSqComputer(): - name = 'pos_computer' - - @staticmethod - def generate_code(generated_dir, K=4): - sympy_functions = generate_residual(K) - header, sympy_code = sympy_into_c(sympy_functions) - - code = "\n#include \"rednose/helpers/common_ekf.h\"\n" - code += "\n#define KDIM %d\n" % K - code += "extern \"C\" {\n" - code += sympy_code - code += "\n" + open(os.path.join(TEMPLATE_DIR, "compute_pos.c"), encoding='utf-8').read() + "\n" - code += "}\n" - - header += "\nvoid compute_pos(double *to_c, double *in_poses, double *in_img_positions, double *param, double *pos);\n" - - filename = f"{LstSqComputer.name}_{K}" - write_code(generated_dir, filename, code, header) - - def __init__(self, generated_dir, K=4, MIN_DEPTH=2, MAX_DEPTH=500): - self.to_c = rot_matrix(-np.pi / 2, -np.pi / 2, 0) - self.MAX_DEPTH = MAX_DEPTH - self.MIN_DEPTH = MIN_DEPTH - - name = f"{LstSqComputer.name}_{K}" - ffi, lib = load_code(generated_dir, name) - - # wrap c functions - def residual_jac(x, poses, img_positions): - out = np.zeros(((K * 2, 3)), dtype=np.float64) - lib.jac_fun(ffi.cast("double *", x.ctypes.data), - ffi.cast("double *", poses.ctypes.data), - ffi.cast("double *", img_positions.ctypes.data), - ffi.cast("double *", out.ctypes.data)) - return out - self.residual_jac = residual_jac - - def residual(x, poses, img_positions): - out = np.zeros((K * 2), dtype=np.float64) - lib.res_fun(ffi.cast("double *", x.ctypes.data), - ffi.cast("double *", poses.ctypes.data), - ffi.cast("double *", img_positions.ctypes.data), - ffi.cast("double *", out.ctypes.data)) - return out - self.residual = residual - - def compute_pos_c(poses, img_positions): - pos = np.zeros(3, dtype=np.float64) - param = np.zeros(3, dtype=np.float64) - # Can't be a view for the ctype - img_positions = np.copy(img_positions) - lib.compute_pos(ffi.cast("double *", self.to_c.ctypes.data), - ffi.cast("double *", poses.ctypes.data), - ffi.cast("double *", img_positions.ctypes.data), - ffi.cast("double *", param.ctypes.data), - ffi.cast("double *", pos.ctypes.data)) - return pos, param - self.compute_pos_c = compute_pos_c - - def compute_pos(self, poses, img_positions, debug=False): - pos, param = self.compute_pos_c(poses, img_positions) - # pos, param = self.compute_pos_python(poses, img_positions) - - depth = 1 / param[2] - if debug: - # orient_err_jac = self.orient_error_jac(param, poses, img_positions, np.zeros(3)).reshape((-1,2,3)) - jac = self.residual_jac(param, poses, img_positions).reshape((-1, 2, 3)) - res = self.residual(param, poses, img_positions).reshape((-1, 2)) - return pos, param, res, jac # , orient_err_jac - elif (self.MIN_DEPTH < depth < self.MAX_DEPTH): - return pos - else: - return None - - def gauss_newton(self, fun, jac, x, args): - poses, img_positions = args - delta = 1 - counter = 0 - while abs(np.linalg.norm(delta)) > 1e-4 and counter < 30: - delta = np.linalg.pinv(jac(x, poses, img_positions)).dot(fun(x, poses, img_positions)) - x = x - delta - counter += 1 - return [x] - - def compute_pos_python(self, poses, img_positions, check_quality=False): - import scipy.optimize as opt - - # This procedure is also described - # in the MSCKF paper (Mourikis et al. 2007) - x = np.array([img_positions[-1][0], - img_positions[-1][1], 0.1]) - res = opt.leastsq(self.residual, x, Dfun=self.residual_jac, args=(poses, img_positions)) # scipy opt - # res = self.gauss_newton(self.residual, self.residual_jac, x, (poses, img_positions)) # diy gauss_newton - - alpha, beta, rho = res[0] - rot_0_to_g = (rotations_from_quats(poses[-1, 3:])).dot(self.to_c.T) - return (rot_0_to_g.dot(np.array([alpha, beta, 1]))) / rho + poses[-1, :3] - - -# EXPERIMENTAL CODE -def unroll_shutter(img_positions, poses, v, rot_rates, ecef_pos): - # only speed correction for now - t_roll = 0.016 # 16ms rolling shutter? - vroll, vpitch, vyaw = rot_rates - A = 0.5 * np.array([[-1, -vroll, -vpitch, -vyaw], - [vroll, 0, vyaw, -vpitch], - [vpitch, -vyaw, 0, vroll], - [vyaw, vpitch, -vroll, 0]]) - q_dot = A.dot(poses[-1][3:7]) - v = np.append(v, q_dot) - v = np.array([v[0], v[1], v[2], 0, 0, 0, 0]) - current_pose = poses[-1] + v * 0.05 - poses = np.vstack((current_pose, poses)) - dt = -img_positions[:, 1] * t_roll / 0.48 - errs = project(poses, ecef_pos) - project(poses + np.atleast_2d(dt).T.dot(np.atleast_2d(v)), ecef_pos) - return img_positions - errs - - -def project(poses, ecef_pos): - img_positions = np.zeros((len(poses), 2)) - for i, p in enumerate(poses): - cam_frame = rotations_from_quats(p[3:]).T.dot(ecef_pos - p[:3]) - img_positions[i] = np.array([cam_frame[1] / cam_frame[0], cam_frame[2] / cam_frame[0]]) - return img_positions - - -if __name__ == "__main__": - K = int(sys.argv[1].split("_")[-1]) - generated_dir = sys.argv[2] - LstSqComputer.generate_code(generated_dir, K=K) diff --git a/rednose_repo/site_scons/site_tools/rednose_filter.py b/rednose_repo/site_scons/site_tools/rednose_filter.py new file mode 100644 index 0000000000..1a26a3b966 --- /dev/null +++ b/rednose_repo/site_scons/site_tools/rednose_filter.py @@ -0,0 +1,48 @@ +import platform + +from SCons.Script import Dir, File + + +def compile_single_filter(env, target, filter_gen_script, output_dir, extra_gen_artifacts, script_deps): + generated_src_files = [File(f) for f in [f'{output_dir}/{target}.cpp', f'{output_dir}/{target}.h']] + extra_generated_files = [File(f'{output_dir}/{x}') for x in extra_gen_artifacts] + generator_file = File(filter_gen_script) + + env.Command(generated_src_files + extra_generated_files, + [generator_file] + script_deps, f"{File(generator_file).relpath} {target} {Dir(output_dir).relpath}") + + generated_cc_file = File(generated_src_files[:1]) + + return generated_cc_file + + +class BaseRednoseCompileMethod: + def __init__(self, base_py_deps, base_cc_deps): + self.base_py_deps = base_py_deps + self.base_cc_deps = base_cc_deps + + +class CompileFilterMethod(BaseRednoseCompileMethod): + def __call__(self, env, target, filter_gen_script, output_dir, extra_gen_artifacts=[], gen_script_deps=[]): + objects = compile_single_filter(env, target, filter_gen_script, output_dir, extra_gen_artifacts, self.base_py_deps + gen_script_deps) + linker_flags = env.get("LINKFLAGS", []) + if platform.system() == "Darwin": + linker_flags = ["-undefined", "dynamic_lookup"] + lib_target = env.SharedLibrary(f'{output_dir}/{target}', [self.base_cc_deps, objects], LINKFLAGS=linker_flags) + + return lib_target + + +def generate(env): + templates = env.Glob("$REDNOSE_ROOT/rednose/templates/*") + sympy_helpers = env.File("$REDNOSE_ROOT/rednose/helpers/sympy_helpers.py") + ekf_sym = env.File("$REDNOSE_ROOT/rednose/helpers/ekf_sym.py") + + gen_script_deps = templates + [sympy_helpers, ekf_sym] + filter_lib_deps = [] + + env.AddMethod(CompileFilterMethod(gen_script_deps, filter_lib_deps), "RednoseCompileFilter") + + +def exists(env): + return True diff --git a/release/build_devel.sh b/release/build_devel.sh index ca04c56f1e..8b6816e423 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -22,6 +22,7 @@ pre-commit uninstall || true echo "[-] bringing master-ci and devel in sync T=$SECONDS" cd $TARGET_DIR + git fetch --depth 1 origin master-ci git fetch --depth 1 origin devel diff --git a/release/build_release.sh b/release/build_release.sh index b713876cd6..fc15cf6cdf 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -102,11 +102,4 @@ if [ ! -z "$RELEASE_BRANCH" ]; then git push -f origin $RELEASE_BRANCH:$RELEASE_BRANCH fi -if [ ! -z "$DASHCAM_BRANCH" ]; then - # Create dashcam - git rm selfdrive/car/*/carcontroller.py - git commit -m "create dashcam release from release" - git push -f origin $RELEASE_BRANCH:$DASHCAM_BRANCH -fi - echo "[-] done T=$SECONDS" diff --git a/release/files_common b/release/files_common index 53720aa05a..1158d2c552 100644 --- a/release/files_common +++ b/release/files_common @@ -21,27 +21,8 @@ openpilot/** common/.gitignore common/__init__.py -common/conversions.py -common/gpio.py -common/realtime.py -common/timeout.py -common/ffi_wrapper.py -common/file_helpers.py -common/logging_extra.py -common/numpy_fast.py -common/params.py -common/params_pyx.pyx -common/profiler.py -common/basedir.py -common/dict_helpers.py -common/filter_simple.py -common/stat_live.py -common/spinner.py -common/text_window.py -common/time.py - -common/kalman/.gitignore -common/kalman/* +common/*.py +common/*.pyx common/transformations/__init__.py common/transformations/camera.py @@ -76,7 +57,6 @@ selfdrive/statsd.py system/logmessaged.py system/micd.py -system/swaglog.py system/version.py selfdrive/athena/__init__.py @@ -115,9 +95,7 @@ selfdrive/car/ecu_addrs.py selfdrive/car/isotp_parallel_query.py selfdrive/car/tests/__init__.py selfdrive/car/tests/test_car_interfaces.py -selfdrive/car/torque_data/params.yaml -selfdrive/car/torque_data/substitute.yaml -selfdrive/car/torque_data/override.yaml +selfdrive/car/torque_data/* selfdrive/car/body/*.py selfdrive/car/chrysler/*.py @@ -137,6 +115,7 @@ selfdrive/debug/can_printer.py selfdrive/debug/check_freq.py selfdrive/debug/dump.py selfdrive/debug/filter_log_message.py +selfdrive/debug/format_fingerprints.py selfdrive/debug/get_fingerprint.py selfdrive/debug/uiview.py @@ -146,31 +125,8 @@ selfdrive/debug/vw_mqb_config.py common/SConscript common/version.h -common/prefix.h -common/swaglog.h -common/swaglog.cc -common/statlog.h -common/statlog.cc -common/util.cc -common/util.h -common/queue.h -common/clutil.cc -common/clutil.h -common/params.h -common/params.cc -common/ratekeeper.cc -common/ratekeeper.h -common/watchdog.cc -common/watchdog.h - -common/modeldata.h -common/mat.h -common/timing.h - -common/gpio.cc -common/gpio.h -common/i2c.cc -common/i2c.h +common/*.h +common/*.cc selfdrive/controls/__init__.py selfdrive/controls/controlsd.py @@ -186,7 +142,6 @@ selfdrive/controls/lib/latcontrol_angle.py selfdrive/controls/lib/latcontrol_torque.py selfdrive/controls/lib/latcontrol_pid.py selfdrive/controls/lib/latcontrol.py -selfdrive/controls/lib/lateral_planner.py selfdrive/controls/lib/longcontrol.py selfdrive/controls/lib/longitudinal_planner.py selfdrive/controls/lib/pid.py @@ -198,6 +153,7 @@ selfdrive/controls/lib/lateral_mpc_lib/* selfdrive/controls/lib/longitudinal_mpc_lib/* system/__init__.py +system/*.py system/hardware/__init__.py system/hardware/base.h @@ -234,12 +190,10 @@ selfdrive/locationd/paramsd.py selfdrive/locationd/models/__init__.py selfdrive/locationd/models/.gitignore selfdrive/locationd/models/car_kf.py -selfdrive/locationd/models/gnss_kf.py selfdrive/locationd/models/live_kf.py selfdrive/locationd/models/live_kf.h selfdrive/locationd/models/live_kf.cc selfdrive/locationd/models/constants.py -selfdrive/locationd/models/gnss_helpers.py selfdrive/locationd/torqued.py selfdrive/locationd/calibrationd.py @@ -284,6 +238,12 @@ system/sensord/sensors/*.cc system/sensord/sensors/*.h system/sensord/pigeond.py +system/webrtc/__init__.py +system/webrtc/webrtcd.py +system/webrtc/schema.py +system/webrtc/device/audio.py +system/webrtc/device/video.py + selfdrive/thermald/thermald.py selfdrive/thermald/power_monitoring.py selfdrive/thermald/fan_controller.py @@ -294,19 +254,14 @@ selfdrive/test/helpers.py selfdrive/test/setup_device_ci.sh selfdrive/test/test_onroad.py selfdrive/test/test_time_to_onroad.py -selfdrive/test/pytest-tici.ini selfdrive/ui/.gitignore selfdrive/ui/SConscript selfdrive/ui/*.cc selfdrive/ui/*.h -selfdrive/ui/ui selfdrive/ui/text selfdrive/ui/spinner -selfdrive/ui/soundd/*.cc -selfdrive/ui/soundd/*.h -selfdrive/ui/soundd/soundd -selfdrive/ui/soundd/.gitignore +selfdrive/ui/soundd.py selfdrive/ui/translations/*.ts selfdrive/ui/translations/languages.json selfdrive/ui/update_translations.py @@ -336,12 +291,8 @@ system/camerad/main.cc system/camerad/snapshot/* system/camerad/cameras/camera_common.h system/camerad/cameras/camera_common.cc -system/camerad/cameras/sensor2_i2c.h - -system/camerad/imgproc/conv.cl -system/camerad/imgproc/pool.cl -system/camerad/imgproc/utils.cc -system/camerad/imgproc/utils.h +system/camerad/sensors/*.h +system/camerad/sensors/*.cc selfdrive/manager/__init__.py selfdrive/manager/build.py @@ -443,10 +394,14 @@ third_party/acados/acados_template/** third_party/bootstrap/** third_party/qt5/larch64/bin/** +third_party/maplibre-native-qt/** scripts/update_now.sh scripts/stop_updater.sh +teleoprtc/** + +rednose_repo/site_scons/site_tools/rednose_filter.py rednose/.gitignore rednose/** diff --git a/release/files_pc b/release/files_pc index 13f1b52166..f2bf090f2c 100644 --- a/release/files_pc +++ b/release/files_pc @@ -1,5 +1,3 @@ -third_party/mapbox-gl-native-qt/x86_64/*.so - third_party/libyuv/x86_64/** third_party/snpe/x86_64/** third_party/snpe/x86_64-linux-clang/** diff --git a/release/files_tici b/release/files_tici index ab49de34f6..1771c45138 100644 --- a/release/files_tici +++ b/release/files_tici @@ -1,18 +1,15 @@ third_party/libyuv/larch64/** third_party/snpe/larch64** third_party/snpe/aarch64-ubuntu-gcc7.5/* -third_party/mapbox-gl-native-qt/include/* third_party/acados/larch64/** -system/timezoned.py - system/camerad/cameras/camera_qcom2.cc system/camerad/cameras/camera_qcom2.h system/camerad/cameras/camera_util.cc system/camerad/cameras/camera_util.h system/camerad/cameras/real_debayer.cl -system/sensord/rawgps/* +system/qcomgpsd/* selfdrive/ui/qt/spinner_larch64 selfdrive/ui/qt/text_larch64 diff --git a/release/verify.sh b/release/verify.sh index 56f21183f1..ec5266bd81 100755 --- a/release/verify.sh +++ b/release/verify.sh @@ -6,7 +6,7 @@ RED="\033[0;31m" GREEN="\033[0;32m" CLEAR="\033[0m" -BRANCHES="devel dashcam3 release3" +BRANCHES="devel release3" for b in $BRANCHES; do if git diff --quiet origin/$b origin/$b-staging && [ "$(git rev-parse origin/$b)" = "$(git rev-parse origin/$b-staging)" ]; then printf "%-10s $GREEN ok $CLEAR\n" "$b" diff --git a/selfdrive/assets/sounds/warning_immediate.wav b/selfdrive/assets/sounds/warning_immediate.wav index 9f6f672e28..b1815a9586 100644 Binary files a/selfdrive/assets/sounds/warning_immediate.wav and b/selfdrive/assets/sounds/warning_immediate.wav differ diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index c93b434677..833bf841f5 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -11,7 +11,6 @@ import queue import random import select import socket -import subprocess import sys import tempfile import threading @@ -31,21 +30,16 @@ import cereal.messaging as messaging from cereal import log from cereal.services import SERVICE_LIST from openpilot.common.api import Api -from openpilot.common.basedir import PERSIST from openpilot.common.file_helpers import CallbackReader from openpilot.common.params import Params from openpilot.common.realtime import set_core_affinity -from openpilot.system.hardware import HARDWARE, PC, AGNOS +from openpilot.system.hardware import HARDWARE, PC from openpilot.system.loggerd.xattr_cache import getxattr, setxattr -from openpilot.selfdrive.statsd import STATS_DIR -from openpilot.system.swaglog import cloudlog -from openpilot.system.version import get_commit, get_origin, get_short_branch, get_version +from openpilot.common.swaglog import cloudlog +from openpilot.system.version import get_commit, get_normalized_origin, get_short_branch, get_version from openpilot.system.hardware.hw import Paths -# TODO: use socket constant when mypy recognizes this as a valid attribute -TCP_USER_TIMEOUT = 18 - ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) LOCAL_PORT_WHITELIST = {8022} @@ -85,7 +79,7 @@ class UploadItem: url: str headers: Dict[str, str] created_at: int - id: Optional[str] # noqa: A003 (to match the response from the remote server) + id: Optional[str] retry_count: int = 0 current: bool = False progress: float = 0 @@ -322,9 +316,9 @@ def getMessage(service: str, timeout: int = 1000) -> dict: def getVersion() -> Dict[str, str]: return { "version": get_version(), - "remote": get_origin(''), - "branch": get_short_branch(''), - "commit": get_commit(default=''), + "remote": get_normalized_origin(), + "branch": get_short_branch(), + "commit": get_commit(), } @@ -365,22 +359,6 @@ def listDataDirectory(prefix='') -> List[str]: return scan_dir(Paths.log_root(), prefix) -@dispatcher.add_method -def reboot() -> Dict[str, int]: - sock = messaging.sub_sock("deviceState", timeout=1000) - ret = messaging.recv_one(sock) - if ret is None or ret.deviceState.started: - raise Exception("Reboot unavailable") - - def do_reboot() -> None: - time.sleep(2) - HARDWARE.reboot() - - threading.Thread(target=do_reboot).start() - - return {"success": 1} - - @dispatcher.add_method def uploadFileToUrl(fn: str, url: str, headers: Dict[str, str]) -> UploadFilesToUrlResponse: # this is because mypy doesn't understand that the decorator doesn't change the return type @@ -454,22 +432,20 @@ def cancelUpload(upload_id: Union[str, List[str]]) -> Dict[str, Union[int, str]] cancelled_uploads.update(cancelled_ids) return {"success": 1} - @dispatcher.add_method -def primeActivated(activated: bool) -> Dict[str, int]: - return {"success": 1} +def setRouteViewed(route: str) -> Dict[str, Union[int, str]]: + # maintain a list of the last 10 routes viewed in connect + params = Params() + r = params.get("AthenadRecentlyViewedRoutes", encoding="utf8") + routes = [] if r is None else r.split(",") + routes.append(route) -@dispatcher.add_method -def setBandwithLimit(upload_speed_kbps: int, download_speed_kbps: int) -> Dict[str, Union[int, str]]: - if not AGNOS: - return {"success": 0, "error": "only supported on AGNOS"} + # remove duplicates + routes = list(dict.fromkeys(routes)) - try: - HARDWARE.set_bandwidth_limit(upload_speed_kbps, download_speed_kbps) - return {"success": 1} - except subprocess.CalledProcessError as e: - return {"success": 0, "error": "failed to set limit", "stdout": e.stdout, "stderr": e.stderr} + params.put("AthenadRecentlyViewedRoutes", ",".join(routes[-10:])) + return {"success": 1} def startLocalProxy(global_end_event: threading.Event, remote_ws_uri: str, local_port: int) -> Dict[str, int]: @@ -507,10 +483,10 @@ def startLocalProxy(global_end_event: threading.Event, remote_ws_uri: str, local @dispatcher.add_method def getPublicKey() -> Optional[str]: - if not os.path.isfile(PERSIST + '/comma/id_rsa.pub'): + if not os.path.isfile(Paths.persist_root() + '/comma/id_rsa.pub'): return None - with open(PERSIST + '/comma/id_rsa.pub') as f: + with open(Paths.persist_root() + '/comma/id_rsa.pub') as f: return f.read() @@ -646,6 +622,7 @@ def log_handler(end_event: threading.Event) -> None: def stat_handler(end_event: threading.Event) -> None: + STATS_DIR = Paths.stats_root() while not end_event.is_set(): last_scan = 0. curr_scan = time.monotonic() @@ -675,6 +652,8 @@ def ws_proxy_recv(ws: WebSocket, local_sock: socket.socket, ssock: socket.socket while not (end_event.is_set() or global_end_event.is_set()): try: data = ws.recv() + if isinstance(data, str): + data = data.encode("utf-8") local_sock.sendall(data) except WebSocketTimeoutException: pass @@ -766,10 +745,11 @@ def ws_manage(ws: WebSocket, end_event: threading.Event) -> None: if onroad != onroad_prev: onroad_prev = onroad - sock.setsockopt(socket.IPPROTO_TCP, TCP_USER_TIMEOUT, 16000 if onroad else 0) - sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPIDLE, 7 if onroad else 30) - sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPINTVL, 7 if onroad else 10) - sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPCNT, 2 if onroad else 3) + if sock is not None: + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_USER_TIMEOUT, 16000 if onroad else 0) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPIDLE, 7 if onroad else 30) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPINTVL, 7 if onroad else 10) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPCNT, 2 if onroad else 3) if end_event.wait(5): break diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index 877d8aca03..486e426911 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -5,8 +5,9 @@ from multiprocessing import Process from openpilot.common.params import Params from openpilot.selfdrive.manager.process import launcher -from openpilot.system.swaglog import cloudlog -from openpilot.system.version import get_version, is_dirty +from openpilot.common.swaglog import cloudlog +from openpilot.system.hardware import HARDWARE +from openpilot.system.version import get_version, get_normalized_origin, get_short_branch, get_commit, is_dirty ATHENA_MGR_PID_PARAM = "AthenadPid" @@ -14,7 +15,13 @@ ATHENA_MGR_PID_PARAM = "AthenadPid" def main(): params = Params() dongle_id = params.get("DongleId").decode('utf-8') - cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=is_dirty()) + cloudlog.bind_global(dongle_id=dongle_id, + version=get_version(), + origin=get_normalized_origin(), + branch=get_short_branch(), + commit=get_commit(), + dirty=is_dirty(), + device=HARDWARE.get_device_type()) try: while 1: diff --git a/selfdrive/athena/registration.py b/selfdrive/athena/registration.py index 0ab69371c2..7db94c28c8 100755 --- a/selfdrive/athena/registration.py +++ b/selfdrive/athena/registration.py @@ -9,10 +9,10 @@ from datetime import datetime, timedelta from openpilot.common.api import api_get from openpilot.common.params import Params from openpilot.common.spinner import Spinner -from openpilot.common.basedir import PERSIST from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, PC -from openpilot.system.swaglog import cloudlog +from openpilot.system.hardware.hw import Paths +from openpilot.common.swaglog import cloudlog UNREGISTERED_DONGLE_ID = "UnregisteredDevice" @@ -25,14 +25,13 @@ def is_registered_device() -> bool: def register(show_spinner=False) -> Optional[str]: params = Params() - params.put("SubscriberInfo", HARDWARE.get_subscriber_info()) IMEI = params.get("IMEI", encoding='utf8') HardwareSerial = params.get("HardwareSerial", encoding='utf8') dongle_id: Optional[str] = params.get("DongleId", encoding='utf8') needs_registration = None in (IMEI, HardwareSerial, dongle_id) - pubkey = Path(PERSIST+"/comma/id_rsa.pub") + pubkey = Path(Paths.persist_root()+"/comma/id_rsa.pub") if not pubkey.is_file(): dongle_id = UNREGISTERED_DONGLE_ID cloudlog.warning(f"missing public key: {pubkey}") @@ -42,7 +41,7 @@ def register(show_spinner=False) -> Optional[str]: spinner.update("registering device") # Create registration token, in the future, this key will make JWTs directly - with open(PERSIST+"/comma/id_rsa.pub") as f1, open(PERSIST+"/comma/id_rsa") as f2: + with open(Paths.persist_root()+"/comma/id_rsa.pub") as f1, open(Paths.persist_root()+"/comma/id_rsa") as f2: public_key = f1.read() private_key = f2.read() diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 0ec33c1a27..b2b59d3752 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -1,11 +1,5 @@ #include "selfdrive/boardd/boardd.h" -#include -#include -#include -#include -#include - #include #include #include @@ -13,10 +7,6 @@ #include #include #include -#include -#include -#include -#include #include #include #include @@ -361,7 +351,6 @@ std::optional send_panda_states(PubMaster *pm, const std::vector ps.setIgnitionLine(health.ignition_line_pkt); ps.setIgnitionCan(health.ignition_can_pkt); ps.setControlsAllowed(health.controls_allowed_pkt); - ps.setGasInterceptorDetected(health.gas_interceptor_detected_pkt); ps.setTxBufferOverflow(health.tx_buffer_overflow_pkt); ps.setRxBufferOverflow(health.rx_buffer_overflow_pkt); ps.setGmlanSendErrs(health.gmlan_send_errs_pkt); @@ -373,11 +362,11 @@ std::optional send_panda_states(PubMaster *pm, const std::vector ps.setHeartbeatLost((bool)(health.heartbeat_lost_pkt)); ps.setAlternativeExperience(health.alternative_experience_pkt); ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt)); - ps.setInterruptLoad(health.interrupt_load); + ps.setInterruptLoad(health.interrupt_load_pkt); ps.setFanPower(health.fan_power); ps.setFanStallCount(health.fan_stall_count); - ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid)); - ps.setSpiChecksumErrorCount(health.spi_checksum_error_count); + ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid_pkt)); + ps.setSpiChecksumErrorCount(health.spi_checksum_error_count_pkt); ps.setSbu1Voltage(health.sbu1_voltage_mV / 1000.0f); ps.setSbu2Voltage(health.sbu2_voltage_mV / 1000.0f); diff --git a/selfdrive/boardd/panda_comms.cc b/selfdrive/boardd/panda_comms.cc index bc4e5f5867..e2c78abea2 100644 --- a/selfdrive/boardd/panda_comms.cc +++ b/selfdrive/boardd/panda_comms.cc @@ -2,33 +2,33 @@ #include #include +#include #include "common/swaglog.h" -static int init_usb_ctx(libusb_context **context) { - assert(context != nullptr); - - int err = libusb_init(context); +static libusb_context *init_usb_ctx() { + libusb_context *context = nullptr; + int err = libusb_init(&context); if (err != 0) { LOGE("libusb initialization error"); - return err; + return nullptr; } #if LIBUSB_API_VERSION >= 0x01000106 - libusb_set_option(*context, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO); + libusb_set_option(context, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO); #else - libusb_set_debug(*context, 3); + libusb_set_debug(context, 3); #endif - - return err; + return context; } PandaUsbHandle::PandaUsbHandle(std::string serial) : PandaCommsHandle(serial) { // init libusb ssize_t num_devices; libusb_device **dev_list = NULL; - int err = init_usb_ctx(&ctx); - if (err != 0) { goto fail; } + int err = 0; + ctx = init_usb_ctx(); + if (!ctx) { goto fail; } // connect by serial num_devices = libusb_get_device_list(ctx, &dev_list); @@ -94,16 +94,14 @@ void PandaUsbHandle::cleanup() { } std::vector PandaUsbHandle::list() { + static std::unique_ptr context(init_usb_ctx(), libusb_exit); // init libusb ssize_t num_devices; - libusb_context *context = NULL; libusb_device **dev_list = NULL; std::vector serials; + if (!context) { return serials; } - int err = init_usb_ctx(&context); - if (err != 0) { return serials; } - - num_devices = libusb_get_device_list(context, &dev_list); + num_devices = libusb_get_device_list(context.get(), &dev_list); if (num_devices < 0) { LOGE("libusb can't get device list"); goto finish; @@ -130,9 +128,6 @@ finish: if (dev_list != NULL) { libusb_free_device_list(dev_list, 1); } - if (context) { - libusb_exit(context); - } return serials; } diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 14d272965d..a87613c803 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -12,7 +12,7 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.selfdrive.boardd.set_time import set_time from openpilot.system.hardware import HARDWARE -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog def get_expected_signature(panda: Panda) -> bytes: @@ -93,6 +93,11 @@ def main() -> NoReturn: cloudlog.event("pandad.flash_and_connect", count=count) params.remove("PandaSignatures") + # TODO: remove this in the next AGNOS + # wait until USB is up before counting + if time.monotonic() < 25.: + no_internal_panda_count = 0 + # Handle missing internal panda if no_internal_panda_count > 0: if no_internal_panda_count == 3: diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index dfce0e3710..148ce9a25d 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -32,7 +32,7 @@ class TestBoardd(unittest.TestCase): with Timeout(90, "boardd didn't start"): sm = messaging.SubMaster(['pandaStates']) - while sm.rcv_frame['pandaStates'] < 1 or len(sm['pandaStates']) == 0 or \ + while sm.recv_frame['pandaStates'] < 1 or len(sm['pandaStates']) == 0 or \ any(ps.pandaType == log.PandaState.PandaType.unknown for ps in sm['pandaStates']): sm.update(1000) diff --git a/selfdrive/car/body/carcontroller.py b/selfdrive/car/body/carcontroller.py index 1dad8e796a..d15f11d3a4 100644 --- a/selfdrive/car/body/carcontroller.py +++ b/selfdrive/car/body/carcontroller.py @@ -1,6 +1,5 @@ import numpy as np -from openpilot.common.params import Params from openpilot.common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from openpilot.selfdrive.car.body import bodycan @@ -20,18 +19,13 @@ class CarController: self.frame = 0 self.packer = CANPacker(dbc_name) - # Speed, balance and turn PIDs - self.speed_pid = PIDController(0.115, k_i=0.23, rate=1/DT_CTRL) - self.balance_pid = PIDController(1300, k_i=0, k_d=280, rate=1/DT_CTRL) + # PIDs self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) self.torque_r_filtered = 0. self.torque_l_filtered = 0. - params = Params() - self.wheeled_body = params.get("WheeledBody") - @staticmethod def deadband_filter(torque, deadband): if torque > 0: @@ -55,17 +49,7 @@ class CarController: speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. speed_error = speed_desired - speed_measured - if self.wheeled_body is None: - freeze_integrator = ((speed_error < 0 and self.speed_pid.error_integral <= -MAX_POS_INTEGRATOR) or - (speed_error > 0 and self.speed_pid.error_integral >= MAX_POS_INTEGRATOR)) - angle_setpoint = self.speed_pid.update(speed_error, freeze_integrator=freeze_integrator) - - # Clip angle error, this is enough to get up from stands - angle_error = np.clip((-CC.orientationNED[1]) - angle_setpoint, -MAX_ANGLE_ERROR, MAX_ANGLE_ERROR) - angle_error_rate = np.clip(-CC.angularVelocity[1], -1., 1.) - torque = self.balance_pid.update(angle_error, error_rate=angle_error_rate) - else: - torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) + torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) turn_error = speed_diff_measured - speed_diff_desired diff --git a/selfdrive/car/body/fingerprints.py b/selfdrive/car/body/fingerprints.py new file mode 100644 index 0000000000..6efaabc137 --- /dev/null +++ b/selfdrive/car/body/fingerprints.py @@ -0,0 +1,28 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.body.values import CAR + +Ecu = car.CarParams.Ecu + +# debug ecu fw version is the git hash of the firmware + + +FINGERPRINTS = { + CAR.BODY: [{ + 513: 8, 516: 8, 514: 3, 515: 4 + }], +} + +FW_VERSIONS = { + CAR.BODY: { + (Ecu.engine, 0x720, None): [ + b'0.0.01', + b'0.3.00a', + b'02/27/2022', + ], + (Ecu.debug, 0x721, None): [ + b'166bd860', + b'dc780f85', + ], + }, +} diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py index ce811ad221..33119bf0fd 100644 --- a/selfdrive/car/body/values.py +++ b/selfdrive/car/body/values.py @@ -30,11 +30,6 @@ CAR_INFO: Dict[str, CarInfo] = { CAR.BODY: CarInfo("comma body", package="All"), } -FINGERPRINTS = { - CAR.BODY: [{ - 513: 8, 516: 8, 514: 3, 515: 4, - }], -} FW_QUERY_CONFIG = FwQueryConfig( requests=[ @@ -46,20 +41,6 @@ FW_QUERY_CONFIG = FwQueryConfig( ], ) -FW_VERSIONS = { - CAR.BODY: { - (Ecu.engine, 0x720, None): [ - b'0.0.01', - b'02/27/2022', - b'0.3.00a', - ], - # git hash of the firmware used - (Ecu.debug, 0x721, None): [ - b'166bd860', - b'dc780f85', - ], - }, -} DBC = { CAR.BODY: dbc_dict('comma_body', None), diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 5c1234258e..95028e10c5 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -10,7 +10,7 @@ from openpilot.selfdrive.car.interfaces import get_interface_attr from openpilot.selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from openpilot.selfdrive.car.vin import get_vin, is_valid_vin, VIN_UNKNOWN from openpilot.selfdrive.car.fw_versions import get_fw_versions_ordered, get_present_ecus, match_fw_to_car, set_obd_multiplexing -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog import cereal.messaging as messaging from openpilot.selfdrive.car import gen_empty_fingerprint @@ -127,9 +127,6 @@ def fingerprint(logcan, sendcan, num_pandas): start_time = time.monotonic() if not skip_fw_query: - # Vin query only reliably works through OBDII - bus = 1 - cached_params = params.get("CarParamsCache") if cached_params is not None: with car.CarParams.from_bytes(cached_params) as cached_params: @@ -139,20 +136,23 @@ def fingerprint(logcan, sendcan, num_pandas): if cached_params is not None and len(cached_params.carFw) > 0 and \ cached_params.carVin is not VIN_UNKNOWN and not disable_fw_cache: cloudlog.warning("Using cached CarParams") - vin, vin_rx_addr = cached_params.carVin, 0 + vin_rx_addr, vin_rx_bus, vin = -1, -1, cached_params.carVin car_fw = list(cached_params.carFw) cached = True else: cloudlog.warning("Getting VIN & FW versions") + # enable OBD multiplexing for VIN query + # NOTE: this takes ~0.1s and is relied on to allow sendcan subscriber to connect in time set_obd_multiplexing(params, True) - vin_rx_addr, vin = get_vin(logcan, sendcan, bus) + # VIN query only reliably works through OBDII + vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (0, 1)) ecu_rx_addrs = get_present_ecus(logcan, sendcan, num_pandas=num_pandas) car_fw = get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, num_pandas=num_pandas) cached = False exact_fw_match, fw_candidates = match_fw_to_car(car_fw) else: - vin, vin_rx_addr = VIN_UNKNOWN, 0 + vin_rx_addr, vin_rx_bus, vin = -1, -1, VIN_UNKNOWN exact_fw_match, fw_candidates, car_fw = True, set(), [] cached = False @@ -162,7 +162,7 @@ def fingerprint(logcan, sendcan, num_pandas): cloudlog.warning("VIN %s", vin) params.put("CarVin", vin) - # disable OBD multiplexing for potential ECU knockouts + # disable OBD multiplexing for CAN fingerprinting and potential ECU knockouts set_obd_multiplexing(params, False) params.put_bool("FirmwareQueryDone", True) @@ -187,8 +187,8 @@ def fingerprint(logcan, sendcan, num_pandas): source = car.CarParams.FingerprintSource.fixed cloudlog.event("fingerprinted", car_fingerprint=car_fingerprint, source=source, fuzzy=not exact_match, cached=cached, - fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), vin_rx_addr=vin_rx_addr, fingerprints=finger, - fw_query_time=fw_query_time, error=True) + fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), vin_rx_addr=vin_rx_addr, vin_rx_bus=vin_rx_bus, + fingerprints=repr(finger), fw_query_time=fw_query_time, error=True) return car_fingerprint, finger, vin, car_fw, source, exact_match @@ -196,7 +196,7 @@ def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1): candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(logcan, sendcan, num_pandas) if candidate is None: - cloudlog.event("car doesn't match any fingerprints", fingerprints=fingerprints, error=True) + cloudlog.event("car doesn't match any fingerprints", fingerprints=repr(fingerprints), error=True) candidate = "mock" CarInterface, CarController, CarState = interfaces[candidate] @@ -207,3 +207,15 @@ def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1): CP.fuzzyFingerprint = not exact_match return CarInterface(CP, CarController, CarState), CP + +def write_car_param(fingerprint="mock"): + params = Params() + CarInterface, _, _ = interfaces[fingerprint] + CP = CarInterface.get_non_essential_params(fingerprint) + params.put("CarParams", CP.to_bytes()) + +def get_demo_car_params(): + fingerprint="mock" + CarInterface, _, _ = interfaces[fingerprint] + CP = CarInterface.get_non_essential_params(fingerprint) + return CP diff --git a/selfdrive/car/chrysler/fingerprints.py b/selfdrive/car/chrysler/fingerprints.py new file mode 100644 index 0000000000..1df514e79b --- /dev/null +++ b/selfdrive/car/chrysler/fingerprints.py @@ -0,0 +1,646 @@ +from cereal import car +from openpilot.selfdrive.car.chrysler.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.PACIFICA_2017_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68239262AH', + b'68239262AI', + b'68239262AJ', + b'68239263AH', + b'68239263AJ', + ], + (Ecu.srs, 0x744, None): [ + b'68238840AH', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'68226356AI', + ], + (Ecu.eps, 0x75a, None): [ + b'68288309AC', + b'68288309AD', + ], + (Ecu.engine, 0x7e0, None): [ + b'68277480AV ', + b'68277480AX ', + b'68277480AZ ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05190175BF', + b'05190175BH', + b'05190226AK', + ], + }, + CAR.PACIFICA_2018: { + (Ecu.combinationMeter, 0x742, None): [ + b'68227902AF', + b'68227902AG', + b'68227902AH', + b'68360252AC', + ], + (Ecu.srs, 0x744, None): [ + b'68211617AF', + b'68211617AG', + b'68358974AC', + b'68405937AA', + ], + (Ecu.abs, 0x747, None): [ + b'68222747AG', + b'68330876AA', + b'68330876AB', + b'68352227AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'68226356AF', + b'68226356AH', + b'68226356AI', + ], + (Ecu.eps, 0x75a, None): [ + b'68288891AE', + b'68378884AA', + b'68525338AA', + b'68525338AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68267018AO ', + b'68267020AJ ', + b'68303534AJ ', + b'68340762AD ', + b'68340764AD ', + b'68352652AE ', + b'68366851AH ', + b'68366853AE ', + b'68372861AF ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'68277370AJ', + b'68277370AM', + b'68277372AD', + b'68277372AN', + b'68277374AA', + b'68277374AB', + b'68277374AD', + b'68277374AN', + b'68367471AC', + b'68380571AB', + ], + }, + CAR.PACIFICA_2020: { + (Ecu.combinationMeter, 0x742, None): [ + b'68405327AC', + b'68436233AB', + b'68436233AC', + b'68436250AE', + b'68529067AA', + b'68594993AB', + ], + (Ecu.srs, 0x744, None): [ + b'68405565AB', + b'68405565AC', + b'68444299AC', + b'68480708AC', + b'68526663AB', + ], + (Ecu.abs, 0x747, None): [ + b'68397394AA', + b'68433480AB', + b'68453575AF', + b'68577676AA', + b'68593395AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'04672758AB', + b'68417813AF', + b'68540436AA', + b'68540436AC', + b'68540436AD', + b'68598670AB', + ], + (Ecu.eps, 0x75a, None): [ + b'68416742AA', + b'68460393AA', + b'68460393AB', + b'68494461AB', + b'68524936AA', + b'68524936AB', + b'68525338AB', + b'68594340AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68413871AD ', + b'68413871AE ', + b'68413871AH ', + b'68413871AI ', + b'68413873AI ', + b'68443120AE ', + b'68443123AC ', + b'68443125AC ', + b'68526752AD ', + b'68526752AE ', + b'68526754AE ', + b'68536264AE ', + b'68700306AB ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'68414271AC', + b'68414271AD', + b'68414275AC', + b'68443154AB', + b'68443155AC', + b'68443158AB', + b'68501050AD', + b'68527221AB', + b'68527223AB', + b'68586231AD', + ], + }, + CAR.PACIFICA_2018_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68358439AE', + b'68358439AG', + ], + (Ecu.srs, 0x744, None): [ + b'68358990AC', + b'68405939AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + ], + (Ecu.eps, 0x75a, None): [ + b'68288309AD', + b'68525339AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'68366580AI ', + b'68366580AK ', + b'68366580AM ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05190226AI', + b'05190226AK', + b'05190226AM', + ], + }, + CAR.PACIFICA_2019_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68405292AC', + b'68434956AC', + b'68434956AD', + b'68434960AE', + b'68434960AF', + b'68529064AB', + b'68594990AB', + ], + (Ecu.srs, 0x744, None): [ + b'68405567AB', + b'68405567AC', + b'68453076AD', + b'68480710AC', + b'68526665AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AB', + b'68417813AF', + b'68540436AA', + b'68540436AB', + b'68540436AC', + b'68540436AD', + b'68598670AB', + b'68598670AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68416741AA', + b'68460392AA', + b'68525339AA', + b'68525339AB', + b'68594341AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68416680AE ', + b'68416680AF ', + b'68416680AG ', + b'68444228AD ', + b'68444228AE ', + b'68444228AF ', + b'68499122AD ', + b'68499122AE ', + b'68499122AF ', + b'68526772AD ', + b'68526772AH ', + b'68599493AC ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05185116AF', + b'05185116AJ', + b'05185116AK', + b'05190240AP', + b'05190240AQ', + b'05190240AR', + b'05190265AG', + b'05190265AH', + b'05190289AE', + b'68540977AH', + b'68540977AK', + b'68597647AE', + ], + }, + CAR.JEEP_GRAND_CHEROKEE: { + (Ecu.combinationMeter, 0x742, None): [ + b'68302211AC', + b'68302212AD', + b'68302246AC', + b'68331511AC', + b'68331574AC', + b'68331687AC', + b'68340272AD', + ], + (Ecu.srs, 0x744, None): [ + b'68316742AB', + b'68355363AB', + ], + (Ecu.abs, 0x747, None): [ + b'68306178AD', + b'68336276AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672627AB', + b'68332015AB', + ], + (Ecu.eps, 0x75a, None): [ + b'68321644AB', + b'68321644AC', + b'68321646AC', + b'68321648AC', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035920AE ', + b'68284455AI ', + b'68284456AI ', + b'68284477AF ', + b'68325564AH ', + b'68325565AH ', + b'68325565AI ', + b'68325618AD ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035517AH', + b'68311218AC', + b'68311223AF', + b'68311223AG', + b'68361911AE', + b'68361911AF', + b'68361911AH', + b'68361916AD', + ], + }, + CAR.JEEP_GRAND_CHEROKEE_2019: { + (Ecu.combinationMeter, 0x742, None): [ + b'68402703AB', + b'68402704AB', + b'68402708AB', + b'68402971AD', + b'68454144AD', + b'68454152AB', + b'68454156AB', + b'68516650AB', + b'68516651AB', + b'68516669AB', + b'68516671AB', + b'68516683AB', + ], + (Ecu.srs, 0x744, None): [ + b'68355363AB', + b'68355364AB', + ], + (Ecu.abs, 0x747, None): [ + b'68408639AC', + b'68408639AD', + b'68499978AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672788AA', + b'68456722AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68417279AA', + b'68417280AA', + b'68417281AA', + b'68453431AA', + b'68453433AA', + b'68453435AA', + b'68499171AA', + b'68499171AB', + b'68501183AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035674AB ', + b'68412635AG ', + b'68412660AD ', + b'68422860AB', + b'68449435AE ', + b'68496223AA ', + b'68504959AD ', + b'68504960AD ', + b'68504993AC ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035707AA', + b'68419672AC', + b'68419678AB', + b'68423905AB', + b'68449258AC', + b'68495807AA', + b'68495807AB', + b'68503641AC', + b'68503664AC', + ], + }, + CAR.RAM_1500: { + (Ecu.combinationMeter, 0x742, None): [ + b'68294051AG', + b'68294051AI', + b'68294052AG', + b'68294052AH', + b'68294063AG', + b'68294063AH', + b'68294063AI', + b'68434846AC', + b'68434847AC', + b'68434849AC', + b'68434856AC', + b'68434858AC', + b'68434859AC', + b'68434860AC', + b'68453483AC', + b'68453487AD', + b'68453491AC', + b'68453499AD', + b'68453503AC', + b'68453505AC', + b'68453505AD', + b'68453511AC', + b'68453513AC', + b'68453513AD', + b'68453514AD', + b'68505633AB', + b'68510277AG', + b'68510277AH', + b'68510280AG', + b'68510282AG', + b'68510282AH', + b'68510283AG', + b'68527346AE', + b'68527361AD', + b'68527375AD', + b'68527381AE', + b'68527382AE', + b'68527383AD', + b'68527387AE', + b'68527403AC', + b'68546047AF', + b'68631938AA', + b'68631942AA', + ], + (Ecu.srs, 0x744, None): [ + b'68428609AB', + b'68441329AB', + b'68473844AB', + b'68490898AA', + b'68500728AA', + b'68615033AA', + b'68615034AA', + ], + (Ecu.abs, 0x747, None): [ + b'68292406AH', + b'68432418AB', + b'68432418AD', + b'68436004AD', + b'68436004AE', + b'68438454AC', + b'68438454AD', + b'68438456AE', + b'68438456AF', + b'68535469AB', + b'68535470AC', + b'68548900AB', + b'68586307AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672892AB', + b'04672932AB', + b'04672932AC', + b'22DTRHD_AA', + b'68320950AH', + b'68320950AI', + b'68320950AJ', + b'68320950AL', + b'68320950AM', + b'68454268AB', + b'68475160AE', + b'68475160AF', + b'68475160AG', + ], + (Ecu.eps, 0x75a, None): [ + b'21590101AA', + b'21590101AB', + b'68273275AF', + b'68273275AG', + b'68273275AH', + b'68312176AE', + b'68312176AG', + b'68440789AC', + b'68466110AA', + b'68466110AB', + b'68469901AA', + b'68469907AA', + b'68522583AA', + b'68522583AB', + b'68522584AA', + b'68522585AB', + b'68552788AA', + b'68552789AA', + b'68552790AA', + b'68552791AB', + b'68552794AA', + b'68585106AB', + b'68585107AB', + b'68585108AB', + b'68585109AB', + b'68585112AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035699AG ', + b'05036026AB ', + b'05036065AE ', + b'05036066AE ', + b'05149368AA ', + b'05149591AD ', + b'05149591AE ', + b'05149592AE ', + b'05149599AE ', + b'05149600AD ', + b'05149605AE ', + b'05149846AA ', + b'05149848AA ', + b'05149848AC ', + b'05190341AD', + b'68378695AJ ', + b'68378696AJ ', + b'68378701AI ', + b'68378702AI ', + b'68378710AL ', + b'68378748AL ', + b'68378758AM ', + b'68448163AJ', + b'68448163AK', + b'68448163AL', + b'68448165AG', + b'68448165AK', + b'68455111AC ', + b'68455119AC ', + b'68455145AC ', + b'68455145AE ', + b'68455146AC ', + b'68467915AC ', + b'68467936AC ', + b'68500630AD', + b'68500630AE', + b'68502719AC ', + b'68502722AC ', + b'68502734AF ', + b'68502740AF ', + b'68502741AF ', + b'68502742AC ', + b'68539650AD', + b'68539650AF', + b'68539651AD', + b'68586101AA ', + b'68586105AB ', + b'68629922AC ', + b'68629926AC ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035706AD', + b'05035842AB', + b'05036069AA', + b'05149536AC', + b'05149537AC', + b'05149543AC', + b'68360078AL', + b'68360080AL', + b'68360080AM', + b'68360081AM', + b'68360085AJ', + b'68360085AL', + b'68384328AD', + b'68384332AD', + b'68445531AC', + b'68445533AB', + b'68445536AB', + b'68445537AB', + b'68466081AB', + b'68466087AB', + b'68484466AC', + b'68484467AC', + b'68484471AC', + b'68502994AD', + b'68520867AE', + b'68520867AF', + b'68520870AC', + b'68540431AB', + b'68540433AB', + b'68629936AC', + ], + }, + CAR.RAM_HD: { + (Ecu.combinationMeter, 0x742, None): [ + b'68361606AH', + b'68437735AC', + b'68492693AD', + b'68525485AB', + b'68525487AB', + b'68525498AB', + b'68528791AF', + b'68628474AB', + ], + (Ecu.srs, 0x744, None): [ + b'68399794AC', + b'68428503AA', + b'68428505AA', + b'68428507AA', + ], + (Ecu.abs, 0x747, None): [ + b'68334977AH', + b'68455481AC', + b'68504022AA', + b'68504022AB', + b'68504022AC', + b'68530686AB', + b'68530686AC', + b'68544596AC', + b'68641704AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672895AB', + b'04672934AB', + b'56029827AG', + b'56029827AH', + b'68462657AE', + b'68484694AD', + b'68484694AE', + b'68615489AB', + ], + (Ecu.eps, 0x761, None): [ + b'68421036AC', + b'68507906AB', + b'68534023AC', + ], + (Ecu.engine, 0x7e0, None): [ + b'52370131AF', + b'52370231AF', + b'52370231AG', + b'52370491AA', + b'52370931CT', + b'52401032AE', + b'52421132AF', + b'52421332AF', + b'68527616AD ', + b'M2370131MB', + b'M2421132MB', + ], + }, + CAR.DODGE_DURANGO: { + (Ecu.combinationMeter, 0x742, None): [ + b'68454261AD', + b'68471535AE', + ], + (Ecu.srs, 0x744, None): [ + b'68355362AB', + b'68492238AD', + ], + (Ecu.abs, 0x747, None): [ + b'68408639AD', + b'68499978AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'68440581AE', + b'68456722AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68453435AA', + b'68498477AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035786AE ', + b'68449476AE ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035826AC', + b'68449265AC', + ], + }, +} diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index fd030e3ec6..32a4f5dfcf 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -28,13 +28,13 @@ class CarInterface(CarInterfaceBase): CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) if candidate not in RAM_CARS: # Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed. - new_eps_platform = candidate in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019) + new_eps_platform = candidate in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_GRAND_CHEROKEE_2019, CAR.DODGE_DURANGO) new_eps_firmware = any(fw.ecu == 'eps' and fw.fwVersion[:4] >= b"6841" for fw in car_fw) if new_eps_platform or new_eps_firmware: ret.flags |= ChryslerFlags.HIGHER_MIN_STEERING_SPEED.value # Chrysler - if candidate in (CAR.PACIFICA_2017_HYBRID, CAR.PACIFICA_2018, CAR.PACIFICA_2018_HYBRID, CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020): + if candidate in (CAR.PACIFICA_2017_HYBRID, CAR.PACIFICA_2018, CAR.PACIFICA_2018_HYBRID, CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.DODGE_DURANGO): ret.mass = 2242. ret.wheelbase = 3.089 ret.steerRatio = 16.2 # Pacifica Hybrid 2017 @@ -45,7 +45,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00006 # Jeep - elif candidate in (CAR.JEEP_CHEROKEE, CAR.JEEP_CHEROKEE_2019): + elif candidate in (CAR.JEEP_GRAND_CHEROKEE, CAR.JEEP_GRAND_CHEROKEE_2019): ret.mass = 1778 ret.wheelbase = 2.71 ret.steerRatio = 16.7 @@ -80,6 +80,7 @@ class CarInterface(CarInterfaceBase): if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: # TODO: allow these cars to steer down to 13 m/s if already engaged. + # TODO: Durango 2020 may be able to steer to zero once above 38 kph ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. ret.centerToFront = ret.wheelbase * 0.44 diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index af12c60a75..94ff1f1d0f 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -1,4 +1,3 @@ -# ruff: noqa: E501 from enum import IntFlag, StrEnum from dataclasses import dataclass, field from typing import Dict, List, Optional, Union @@ -24,9 +23,12 @@ class CAR(StrEnum): PACIFICA_2018 = "CHRYSLER PACIFICA 2018" PACIFICA_2020 = "CHRYSLER PACIFICA 2020" + # Dodge + DODGE_DURANGO = "DODGE DURANGO 2021" + # Jeep - JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk - JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk + JEEP_GRAND_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk + JEEP_GRAND_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk # Ram RAM_1500 = "RAM 1500 5TH GEN" @@ -65,84 +67,24 @@ class ChryslerCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = { - CAR.PACIFICA_2017_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2017-18"), - CAR.PACIFICA_2018_HYBRID: None, # same platforms + CAR.PACIFICA_2017_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2017"), + CAR.PACIFICA_2018_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2018"), CAR.PACIFICA_2019_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2019-23"), CAR.PACIFICA_2018: ChryslerCarInfo("Chrysler Pacifica 2017-18"), CAR.PACIFICA_2020: [ ChryslerCarInfo("Chrysler Pacifica 2019-20"), - ChryslerCarInfo("Chrysler Pacifica 2021", package="All"), + ChryslerCarInfo("Chrysler Pacifica 2021-23", package="All"), ], - CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), - CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), - CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-23", car_parts=CarParts.common([CarHarness.ram])), + CAR.JEEP_GRAND_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), + CAR.JEEP_GRAND_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), + CAR.DODGE_DURANGO: ChryslerCarInfo("Dodge Durango 2020-21"), + CAR.RAM_1500: ChryslerCarInfo("Ram 1500 2019-24", car_parts=CarParts.common([CarHarness.ram])), CAR.RAM_HD: [ - ChryslerCarInfo("Ram 2500 2020-22", car_parts=CarParts.common([CarHarness.ram])), + ChryslerCarInfo("Ram 2500 2020-24", car_parts=CarParts.common([CarHarness.ram])), ChryslerCarInfo("Ram 3500 2019-22", car_parts=CarParts.common([CarHarness.ram])), ], } -# Unique CAN messages: -# Only the hybrids have 270: 8 -# Only the gas have 55: 8, 416: 7 -# For 564, All 2017 have length 4, whereas 2018-19 have length 8. -# For 924, Pacifica 2017 has length 3, whereas all 2018-19 have length 8. -# For 560, All 2019 have length 8, whereas all 2017-18 have length 4. - -# Jeep Grand Cherokee unique messages: -# 2017 Trailhawk: 618: 8 -# For 924, Trailhawk 2017 has length 3, whereas 2018 V6 has length 8. - -FINGERPRINTS = { - CAR.PACIFICA_2017_HYBRID: [{ - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 840: 8, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8 - }], - CAR.PACIFICA_2018: [{ - 55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8 - }, - { - 55: 8, 58: 6, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 926: 3, 937: 8, 947: 8, 948: 8, 956: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8 - }], - CAR.PACIFICA_2020: [{ - 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 536: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 776: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 886: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1543: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 2015: 8, 2016: 8, 2017:8, 2024: 8, 2025: 8 - }], - CAR.PACIFICA_2018_HYBRID: [{ - 68: 8, 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8 - }, - # based on 9ae7821dc4e92455|2019-07-01--16-42-55 - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2016: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 - }], - CAR.PACIFICA_2019_HYBRID: [{ - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8 - }, - # Based on 0607d2516fc2148f|2019-02-13--23-03-16 - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1537: 8 - }, - # Based on 3c7ce223e3571b54|2019-05-11--20-16-14 - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1562: 8, 1570: 8 - }, - # Based on "8190c7275a24557b|2020-02-24--09-57-23" - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 886: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 8, 1284: 8, 1536: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2015: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8 - }, - { - 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 450: 8, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 886: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2018: 8, 2020: 8, 2026: 8, 2028: 8 - }], - CAR.JEEP_CHEROKEE: [{ - 55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 975: 8, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1543: 8, 1562: 8, 1576: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }, - # Based on c88f65eeaee4003a|2022-08-04--15-37-16 - { - 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 671: 8, 672: 8, 678: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1235: 8, 1242: 8, 1252: 8, 1792: 8, 1798: 8, 1799: 8, 1810: 8, 1813: 8, 1824: 8, 1825: 8, 1840: 8, 1856: 8, 1858: 8, 1859: 8, 1860: 8, 1862: 8, 1863: 8, 1872: 8, 1875: 8, 1879: 8, 1882: 8, 1888: 8, 1892: 8, 1927: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], - CAR.JEEP_CHEROKEE_2019: [{ - # Jeep Grand Cherokee 2019, including most 2020 models - 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1538: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], -} CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(0xf132) @@ -179,203 +121,10 @@ FW_QUERY_CONFIG = FwQueryConfig( ), ], extra_ecus=[ - (Ecu.hybrid, 0x7e2, None), # manages transmission on hybrids - (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids + (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids, NOTE: not on all hybrid platforms ], ) -FW_VERSIONS = { - CAR.JEEP_CHEROKEE_2019: { - (Ecu.combinationMeter, 0x742, None): [ - b'68402971AD', - ], - (Ecu.srs, 0x744, None): [ - b'68355363AB', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AD', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'68456722AC', - ], - (Ecu.eps, 0x75A, None): [ - b'68453431AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035674AB ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035707AA', - ], - }, - - CAR.RAM_1500: { - (Ecu.combinationMeter, 0x742, None): [ - b'68294051AG', - b'68294051AI', - b'68294052AG', - b'68294063AG', - b'68294063AH', - b'68294063AI', - b'68434846AC', - b'68434858AC', - b'68434860AC', - b'68453503AC', - b'68453505AC', - b'68453511AC', - b'68453513AD', - b'68453514AD', - b'68510280AG', - b'68510283AG', - b'68527346AE', - b'68527375AD', - b'68527382AE', - ], - (Ecu.srs, 0x744, None): [ - b'68428609AB', - b'68441329AB', - b'68473844AB', - b'68490898AA', - b'68500728AA', - b'68615033AA', - b'68615034AA', - ], - (Ecu.abs, 0x747, None): [ - b'68292406AH', - b'68432418AB', - b'68432418AD', - b'68436004AD', - b'68436004AE', - b'68438454AC', - b'68438454AD', - b'68438456AE', - b'68438456AF', - b'68535469AB', - b'68535470AC', - b'68548900AB', - b'68586307AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672892AB', - b'04672932AB', - b'04672932AC', - b'22DTRHD_AA', - b'68320950AH', - b'68320950AI', - b'68320950AJ', - b'68320950AL', - b'68320950AM', - b'68454268AB', - b'68475160AE', - b'68475160AF', - b'68475160AG', - ], - (Ecu.eps, 0x75A, None): [ - b'21590101AA', - b'21590101AB', - b'68273275AF', - b'68273275AG', - b'68273275AH', - b'68312176AE', - b'68312176AG', - b'68440789AC', - b'68466110AB', - b'68469901AA', - b'68522583AB', - b'68522585AB', - b'68552788AA', - b'68552789AA', - b'68552790AA', - b'68585106AB', - b'68585109AB', - b'68585112AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'05036065AE ', - b'05036066AE ', - b'05149592AE ', - b'05149591AD ', - b'05149846AA ', - b'05149848AA ', - b'68378701AI ', - b'68378748AL ', - b'68378758AM ', - b'68448163AJ', - b'68448165AK', - b'68500630AD', - b'68500630AE', - b'68539650AD', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05149536AC', - b'68360078AL', - b'68360080AM', - b'68360081AM', - b'68360085AL', - b'68384328AD', - b'68384332AD', - b'68445533AB', - b'68484467AC', - b'68502994AD', - b'68520867AE', - b'68540431AB', - ], - }, - - CAR.RAM_HD: { - (Ecu.combinationMeter, 0x742, None): [ - b'68361606AH', - b'68437735AC', - b'68492693AD', - b'68525485AB', - b'68525487AB', - b'68525498AB', - b'68528791AF', - ], - (Ecu.srs, 0x744, None): [ - b'68399794AC', - b'68428503AA', - b'68428505AA', - b'68428507AA', - ], - (Ecu.abs, 0x747, None): [ - b'68334977AH', - b'68455481AC', - b'68504022AA', - b'68504022AB', - b'68504022AC', - b'68530686AB', - b'68530686AC', - b'68544596AC', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672895AB', - b'04672934AB', - b'56029827AG', - b'56029827AH', - b'68462657AE', - b'68484694AD', - b'68484694AE', - ], - (Ecu.eps, 0x761, None): [ - b'68421036AC', - b'68507906AB', - b'68534023AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'52370131AF', - b'52370231AF', - b'52370231AG', - b'52370931CT', - b'52401032AE', - b'52421132AF', - b'52421332AF', - b'68527616AD ', - b'M2370131MB', - b'M2421132MB', - ], - }, -} DBC = { CAR.PACIFICA_2017_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), @@ -383,8 +132,9 @@ DBC = { CAR.PACIFICA_2020: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), CAR.PACIFICA_2018_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), CAR.PACIFICA_2019_HYBRID: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.JEEP_CHEROKEE: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), - CAR.JEEP_CHEROKEE_2019: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.DODGE_DURANGO: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.JEEP_GRAND_CHEROKEE: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), + CAR.JEEP_GRAND_CHEROKEE_2019: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion'), CAR.RAM_1500: dbc_dict('chrysler_ram_dt_generated', None), CAR.RAM_HD: dbc_dict('chrysler_ram_hd_generated', None), } diff --git a/selfdrive/car/disable_ecu.py b/selfdrive/car/disable_ecu.py index c11075342c..1f731f0344 100755 --- a/selfdrive/car/disable_ecu.py +++ b/selfdrive/car/disable_ecu.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog EXT_DIAG_REQUEST = b'\x10\x03' EXT_DIAG_RESPONSE = b'\x50\x03' diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 2e80dde010..f2ce743607 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -244,10 +244,13 @@ class CarInfo: # all the parts needed for the supported car car_parts: CarParts = field(default_factory=CarParts) + def __post_init__(self): + self.make, self.model, self.years = split_name(self.name) + self.year_list = get_year_list(self.years) + def init(self, CP: car.CarParams, all_footnotes: Dict[Enum, int]): self.car_name = CP.carName self.car_fingerprint = CP.carFingerprint - self.make, self.model, self.years = split_name(self.name) # longitudinal column op_long = "Stock" @@ -309,7 +312,6 @@ class CarInfo: self.row[Column.STEERING_TORQUE] = Star.FULL self.all_footnotes = all_footnotes - self.year_list = get_year_list(self.years) self.detail_sentence = self.get_detail_sentence(CP) return self diff --git a/selfdrive/car/ecu_addrs.py b/selfdrive/car/ecu_addrs.py index cff1df79a5..13f7926def 100755 --- a/selfdrive/car/ecu_addrs.py +++ b/selfdrive/car/ecu_addrs.py @@ -8,7 +8,7 @@ from panda.python.uds import SERVICE_TYPE from openpilot.selfdrive.car import make_can_msg from openpilot.selfdrive.car.fw_query_definitions import EcuAddrBusType from openpilot.selfdrive.boardd.boardd import can_list_to_can_capnp -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog def make_tester_present_msg(addr, bus, subaddr=None): diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py index 1d627e4b37..6a7c3c75be 100644 --- a/selfdrive/car/fingerprints.py +++ b/selfdrive/car/fingerprints.py @@ -1,13 +1,12 @@ from openpilot.selfdrive.car.interfaces import get_interface_attr - 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): +def is_valid_for_fingerprint(msg, car_fingerprint: dict[int, int]): adr = msg.address # ignore addresses that are more than 11 bits return (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) or adr >= 0x800 diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index fe9ee404a4..45516d6035 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -4,6 +4,7 @@ from opendbc.can.packer import CANPacker from openpilot.selfdrive.car import apply_std_steer_angle_limits from openpilot.selfdrive.car.ford import fordcan from openpilot.selfdrive.car.ford.values import CANFD_CAR, CarControllerParams +from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX LongCtrlState = car.CarControl.Actuators.LongControlState VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -88,9 +89,8 @@ class CarController: gas = accel if not CC.longActive or gas < CarControllerParams.MIN_GAS: gas = CarControllerParams.INACTIVE_GAS - stopping = CC.actuators.longControlState == LongCtrlState.stopping - can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping)) + can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, v_ego_kph=V_CRUISE_MAX)) ### ui ### send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index 5c787b787a..ef56d23d79 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -18,15 +18,16 @@ class CarState(CarStateBase): self.shifter_values = can_define.dv["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"] self.vehicle_sensors_valid = False - self.hybrid_platform = False + self.unsupported_platform = False def update(self, cp, cp_cam): ret = car.CarState.new_message() - # Hybrid variants experience a bug where a message from the PCM sends invalid checksums, - # we do not support these cars at this time. + # Ford Q3 hybrid variants experience a bug where a message from the PCM sends invalid checksums, + # this must be root-caused before enabling support. Ford Q4 hybrids do not have this problem. # TrnAin_Tq_Actl and its quality flag are only set on ICE platform variants - self.hybrid_platform = cp.vl["VehicleOperatingModes"]["TrnAinTq_D_Qf"] == 0 + self.unsupported_platform = (cp.vl["VehicleOperatingModes"]["TrnAinTq_D_Qf"] == 0 and + self.CP.carFingerprint not in CANFD_CAR) # Occasionally on startup, the ABS module recalibrates the steering pinion offset, so we need to block engagement # The vehicle usually recovers out of this state within a minute of normal driving @@ -53,7 +54,7 @@ class CarState(CarStateBase): ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5) ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) - # ret.espDisabled = False # TODO: find traction control signal + ret.espDisabled = cp.vl["Cluster_Info1_FD1"]["DrvSlipCtlMde_D_Rq"] != 0 # 0 is default mode if self.CP.carFingerprint in CANFD_CAR: # this signal is always 0 on non-CAN FD cars diff --git a/selfdrive/car/ford/fingerprints.py b/selfdrive/car/ford/fingerprints.py new file mode 100644 index 0000000000..a5d465849a --- /dev/null +++ b/selfdrive/car/ford/fingerprints.py @@ -0,0 +1,144 @@ +from cereal import car +from openpilot.selfdrive.car.ford.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.BRONCO_SPORT_MK1: { + (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.ESCAPE_MK4: { + (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.EXPLORER_MK6: { + (Ecu.eps, 0x730, None): [ + b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'P1MC-14D003-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LC5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.F_150_MK14: { + (Ecu.eps, 0x730, None): [ + b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.F_150_LIGHTNING_MK1: { + (Ecu.abs, 0x760, None): [ + b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MUSTANG_MACH_E_MK1: { + (Ecu.eps, 0x730, None): [ + b'LJ9C-14D003-AM\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ9C-14D003-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LK9C-2D053-CK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABS\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FOCUS_MK4: { + (Ecu.eps, 0x730, None): [ + b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAVERICK_MK1: { + (Ecu.eps, 0x730, None): [ + b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-EE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, +} diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index e0086ecbb5..c5ef0900f3 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -118,7 +118,7 @@ def create_lat_ctl2_msg(packer, CAN: CanBus, mode: int, path_offset: float, path return packer.make_can_msg("LateralMotionControl2", CAN.main, values) -def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool): +def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, v_ego_kph: float): """ Creates a CAN message for the Ford ACC Command. @@ -127,13 +127,14 @@ def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: fl Frequency is 50Hz. """ - decel = accel < 0 and long_active values = { "AccBrkTot_A_Rq": accel, # Brake total accel request: [-20|11.9449] m/s^2 "Cmbb_B_Enbl": 1 if long_active else 0, # Enabled: 0=No, 1=Yes "AccPrpl_A_Rq": gas, # Acceleration request: [-5|5.23] m/s^2 + "AccPrpl_A_Pred": -5.0, # Acceleration request: [-5|5.23] m/s^2 "AccResumEnbl_B_Rq": 1 if long_active else 0, + "AccVeh_V_Trg": v_ego_kph, # Target speed: [0|255] km/h # TODO: we may be able to improve braking response by utilizing pre-charging better "AccBrkPrchg_B_Rq": 1 if decel else 0, # Pre-charge brake request: 0=No, 1=Yes "AccBrkDecel_B_Rq": 1 if decel else 0, # Deceleration request: 0=Inactive, 1=Active diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 3045c317ff..cc013fb54b 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -14,13 +14,17 @@ class CarInterface(CarInterfaceBase): @staticmethod def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): ret.carName = "ford" - ret.dashcamOnly = candidate in {CAR.F_150_MK14} + ret.dashcamOnly = candidate in CANFD_CAR ret.radarUnavailable = True ret.steerControlType = car.CarParams.SteerControlType.angle ret.steerActuatorDelay = 0.2 ret.steerLimitTimer = 1.0 + ret.longitudinalTuning.kpBP = [0.] + ret.longitudinalTuning.kpV = [0.5] + ret.longitudinalTuning.kiV = [0.] + CAN = CanBus(fingerprint=fingerprint) cfgs = [get_safety_config(car.CarParams.SafetyModel.ford)] if CAN.main >= 4: @@ -56,6 +60,17 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.0 ret.mass = 2000 + elif candidate == CAR.F_150_LIGHTNING_MK1: + # required trim only on SuperCrew + ret.wheelbase = 3.70 + ret.steerRatio = 16.9 + ret.mass = 2948 + + elif candidate == CAR.MUSTANG_MACH_E_MK1: + ret.wheelbase = 2.984 + ret.steerRatio = 17.0 # guess + ret.mass = 2200 + elif candidate == CAR.FOCUS_MK4: ret.wheelbase = 2.7 ret.steerRatio = 15.0 @@ -94,7 +109,7 @@ class CarInterface(CarInterfaceBase): events = self.create_common_events(ret, extra_gears=[GearShifter.manumatic]) if not self.CS.vehicle_sensors_valid: events.add(car.CarEvent.EventName.vehicleSensorsInvalid) - if self.CS.hybrid_platform: + if self.CS.unsupported_platform: events.add(car.CarEvent.EventName.startupNoControl) ret.events = events.to_msg() diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 716c9b6e58..209bbebae3 100644 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -119,17 +119,23 @@ class RadarInterface(RadarInterfaceBase): self.track_id += 1 valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) - amplitude = msg[f"CAN_DET_AMPLITUDE_{ii:02d}"] # dBsm [-64|63] - if valid and 0 < amplitude <= 15: + if valid: azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] + dRel = cos(azimuth) * dist # m from front of car + yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive - # *** openpilot radar point *** - self.pts[i].dRel = cos(azimuth) * dist # m from front of car - self.pts[i].yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive - self.pts[i].vRel = distRate # m/s + # delphi doesn't notify of track switches, so do it manually + # TODO: refactor this to radard if more radars behave this way + if abs(self.pts[i].vRel - distRate) > 2 or abs(self.pts[i].dRel - dRel) > 5: + self.track_id += 1 + self.pts[i].trackId = self.track_id + + self.pts[i].dRel = dRel + self.pts[i].yRel = yRel + self.pts[i].vRel = distRate self.pts[i].measured = True diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index d11ba4ccf0..c080e02299 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -1,12 +1,12 @@ from collections import defaultdict -from dataclasses import dataclass, field +from dataclasses import dataclass from enum import Enum, StrEnum from typing import Dict, List, Union from cereal import car from openpilot.selfdrive.car import AngleRateLimit, dbc_dict from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarInfo, CarParts, Column, \ - Device + Device from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries Ecu = car.CarParams.Ecu @@ -47,9 +47,11 @@ class CAR(StrEnum): F_150_MK14 = "FORD F-150 14TH GEN" FOCUS_MK4 = "FORD FOCUS 4TH GEN" MAVERICK_MK1 = "FORD MAVERICK 1ST GEN" + F_150_LIGHTNING_MK1 = "FORD F-150 LIGHTNING 1ST GEN" + MUSTANG_MACH_E_MK1 = "FORD MUSTANG MACH-E 1ST GEN" -CANFD_CAR = {CAR.F_150_MK14} +CANFD_CAR = {CAR.F_150_MK14, CAR.F_150_LIGHTNING_MK1, CAR.MUSTANG_MACH_E_MK1} class RADAR: @@ -61,6 +63,8 @@ DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict("ford_lincoln_base # F-150 radar is not yet supported DBC[CAR.F_150_MK14] = dbc_dict("ford_lincoln_base_pt", None) +DBC[CAR.F_150_LIGHTNING_MK1] = dbc_dict("ford_lincoln_base_pt", None) +DBC[CAR.MUSTANG_MACH_E_MK1] = dbc_dict("ford_lincoln_base_pt", None) class Footnote(Enum): @@ -74,11 +78,13 @@ class Footnote(Enum): @dataclass class FordCarInfo(CarInfo): package: str = "Co-Pilot360 Assist+" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.ford_q3])) def init_make(self, CP: car.CarParams): - if CP.carFingerprint in (CAR.BRONCO_SPORT_MK1, CAR.MAVERICK_MK1): - self.car_parts = CarParts([Device.threex_angled_mount, CarHarness.ford_q3]) + harness = CarHarness.ford_q4 if CP.carFingerprint in CANFD_CAR else CarHarness.ford_q3 + if CP.carFingerprint in (CAR.BRONCO_SPORT_MK1, CAR.MAVERICK_MK1, CAR.F_150_MK14): + self.car_parts = CarParts([Device.threex_angled_mount, harness]) + else: + self.car_parts = CarParts([Device.threex, harness]) CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { @@ -88,10 +94,12 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { FordCarInfo("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering"), ], CAR.EXPLORER_MK6: [ - FordCarInfo("Ford Explorer 2020-22"), + FordCarInfo("Ford Explorer 2020-23"), FordCarInfo("Lincoln Aviator 2020-21", "Co-Pilot360 Plus"), ], CAR.F_150_MK14: FordCarInfo("Ford F-150 2023", "Co-Pilot360 Active 2.0"), + CAR.F_150_LIGHTNING_MK1: FordCarInfo("Ford F-150 Lightning 2021-23", "Co-Pilot360 Active 2.0"), + CAR.MUSTANG_MACH_E_MK1: FordCarInfo("Ford Mustang Mach-E 2021-23", "Co-Pilot360 Active 2.0"), CAR.FOCUS_MK4: FordCarInfo("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS]), CAR.MAVERICK_MK1: [ FordCarInfo("Ford Maverick 2022", "LARIAT Luxury"), @@ -103,171 +111,16 @@ FW_QUERY_CONFIG = FwQueryConfig( requests=[ # CAN and CAN FD queries are combined. # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus - # TODO: properly handle auxiliary requests to separate queries and add back whitelists Request( [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - # whitelist_ecus=[Ecu.engine], - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - # whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire], bus=0, auxiliary=True, ), ], extra_ecus=[ + # We are unlikely to get a response from the PCM from behind the gateway + (Ecu.engine, 0x7e0, None), (Ecu.shiftByWire, 0x732, None), ], ) - -FW_VERSIONS = { - CAR.BRONCO_SPORT_MK1: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7E0, None): [ - b'M1PA-14C204-GF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'N1PA-14C204-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'N1PA-14C204-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.ESCAPE_MK4: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7E0, None): [ - b'LX6A-14C204-BJV\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6A-14C204-BJX\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6A-14C204-CNG\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6A-14C204-DPK\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'MX6A-14C204-BEF\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'MX6A-14C204-BEJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'MX6A-14C204-CAB\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NX6A-14C204-BLE\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.EXPLORER_MK6: { - (Ecu.eps, 0x730, None): [ - b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7E0, None): [ - b'LB5A-14C204-ATJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5A-14C204-AUJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5A-14C204-AZL\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5A-14C204-BUJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'MB5A-14C204-RC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NB5A-14C204-AZD\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NB5A-14C204-HB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.F_150_MK14: { - (Ecu.eps, 0x730, None): [ - b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7E0, None): [ - b'PL3A-14C204-BRB\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FOCUS_MK4: { - (Ecu.eps, 0x730, None): [ - b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7E0, None): [ - b'JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAVERICK_MK1: { - (Ecu.eps, 0x730, None): [ - b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7E0, None): [ - b'NZ6A-14C204-AAA\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6A-14C204-PA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6A-14C204-ZA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6A-14C204-BE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6A-14C204-JC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6A-14C204-JE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py index 1caedcd321..36e6794d2c 100755 --- a/selfdrive/car/fw_query_definitions.py +++ b/selfdrive/car/fw_query_definitions.py @@ -9,6 +9,15 @@ import panda.python.uds as uds AddrType = Tuple[int, Optional[int]] EcuAddrBusType = Tuple[int, Optional[int], int] +EcuAddrSubAddr = Tuple[int, int, Optional[int]] + +LiveFwVersions = Dict[AddrType, Set[bytes]] +OfflineFwVersions = Dict[str, Dict[EcuAddrSubAddr, List[bytes]]] + +# A global list of addresses we will only ever consider for VIN responses +# engine, hybrid controller, Ford abs, Hyundai CAN FD cluster, 29-bit engine, PGM-FI +# TODO: move these to each brand's FW query config +STANDARD_VIN_ADDRS = [0x7e0, 0x7e2, 0x760, 0x7c6, 0x18da10f1, 0x18da0ef1] def p16(val): @@ -53,6 +62,12 @@ class StdQueries: UDS_VIN_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN) UDS_VIN_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(uds.DATA_IDENTIFIER_TYPE.VIN) + GM_VIN_REQUEST = b'\x1a\x90' + GM_VIN_RESPONSE = b'\x5a\x90' + + KWP_VIN_REQUEST = b'\x21\x81' + KWP_VIN_RESPONSE = b'\x61\x81' + @dataclass class Request: @@ -79,7 +94,7 @@ class FwQueryConfig: extra_ecus: List[Tuple[capnp.lib.capnp._EnumModule, int, Optional[int]]] = field(default_factory=list) # Function a brand can implement to provide better fuzzy matching. Takes in FW versions, # returns set of candidates. Only will match if one candidate is returned - match_fw_to_car_fuzzy: Optional[Callable[[Dict[AddrType, Set[bytes]]], Set[str]]] = None + match_fw_to_car_fuzzy: Optional[Callable[[LiveFwVersions, OfflineFwVersions], Set[str]]] = None def __post_init__(self): for i in range(len(self.requests)): @@ -87,3 +102,13 @@ class FwQueryConfig: new_request = copy.deepcopy(self.requests[i]) new_request.bus += 4 self.requests.append(new_request) + + def get_all_ecus(self, offline_fw_versions: OfflineFwVersions, + include_extra_ecus: bool = True) -> set[EcuAddrSubAddr]: + # Add ecus in database + extra ecus + brand_ecus = {ecu for ecus in offline_fw_versions.values() for ecu in ecus} + + if include_extra_ecus: + brand_ecus |= set(self.extra_ecus) + + return brand_ecus diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 45c4967cb8..6c02e69503 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 from collections import defaultdict -from typing import Any, DefaultDict, Dict, List, Optional, Set +from typing import Any, DefaultDict, Dict, Iterator, List, Optional, Set, TypeVar from tqdm import tqdm import capnp @@ -8,24 +8,26 @@ import panda.python.uds as uds from cereal import car from openpilot.common.params import Params from openpilot.selfdrive.car.ecu_addrs import get_ecu_addrs -from openpilot.selfdrive.car.fw_query_definitions import AddrType, EcuAddrBusType +from openpilot.selfdrive.car.fw_query_definitions import AddrType, EcuAddrBusType, FwQueryConfig from openpilot.selfdrive.car.interfaces import get_interface_attr from openpilot.selfdrive.car.fingerprints import FW_VERSIONS from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog Ecu = car.CarParams.Ecu ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] FUZZY_EXCLUDE_ECUS = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug] -FW_QUERY_CONFIGS = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) +FW_QUERY_CONFIGS: dict[str, FwQueryConfig] = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) MODEL_TO_BRAND = {c: b for b, e in VERSIONS.items() for c in e} REQUESTS = [(brand, config, r) for brand, config in FW_QUERY_CONFIGS.items() for r in config.requests] +T = TypeVar('T') -def chunks(l, n=128): + +def chunks(l: List[T], n: int = 128) -> Iterator[List[T]]: for i in range(0, len(l), n): yield l[i:i + n] @@ -45,16 +47,6 @@ def build_fw_dict(fw_versions: List[capnp.lib.capnp._DynamicStructBuilder], return dict(fw_versions_dict) -def get_brand_addrs() -> Dict[str, Set[AddrType]]: - brand_addrs: DefaultDict[str, Set[AddrType]] = defaultdict(set) - for brand, cars in VERSIONS.items(): - # Add ecus in database + extra ecus to match against - brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in FW_QUERY_CONFIGS[brand].extra_ecus} - for fw in cars.values(): - brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in fw.keys()} - return dict(brand_addrs) - - def match_fw_to_car_fuzzy(live_fw_versions, match_brand=None, log=True, exclude=None): """Do a fuzzy FW match. This function will return a match, and the number of firmware version that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars @@ -105,11 +97,14 @@ def match_fw_to_car_fuzzy(live_fw_versions, match_brand=None, log=True, exclude= return set() -def match_fw_to_car_exact(live_fw_versions, match_brand=None, log=True) -> Set[str]: +def match_fw_to_car_exact(live_fw_versions, match_brand=None, log=True, extra_fw_versions=None) -> Set[str]: """Do an exact FW match. Returns all cars that match the given FW versions for a list of "essential" ECUs. If an ECU is not considered essential the FW version can be missing to get a fingerprint, but if it's present it needs to match the database.""" + if extra_fw_versions is None: + extra_fw_versions = {} + invalid = set() candidates = {c: f for c, f in FW_VERSIONS.items() if is_brand(MODEL_TO_BRAND[c], match_brand)} @@ -117,12 +112,14 @@ def match_fw_to_car_exact(live_fw_versions, match_brand=None, log=True) -> Set[s for candidate, fws in candidates.items(): config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]] for ecu, expected_versions in fws.items(): + expected_versions = expected_versions + extra_fw_versions.get(candidate, {}).get(ecu, []) ecu_type = ecu[0] addr = ecu[1:] found_versions = live_fw_versions.get(addr, set()) if not len(found_versions): # Some models can sometimes miss an ecu, or show on two different addresses + # FIXME: this logic can be improved to be more specific, should require one of the two addresses if candidate in config.non_essential_ecus.get(ecu_type, []): continue @@ -159,7 +156,7 @@ def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True, log=True): # If specified and no matches so far, fall back to brand's fuzzy fingerprinting function config = FW_QUERY_CONFIGS[brand] if not exact_match and not len(matches) and config.match_fw_to_car_fuzzy is not None: - matches |= config.match_fw_to_car_fuzzy(fw_versions_dict) + matches |= config.match_fw_to_car_fuzzy(fw_versions_dict, VERSIONS[brand]) if len(matches): return exact_match, matches @@ -179,22 +176,21 @@ def get_present_ecus(logcan, sendcan, num_pandas=1) -> Set[EcuAddrBusType]: if r.bus > num_pandas * 4 - 1: continue - for brand_versions in VERSIONS[brand].values(): - for ecu_type, addr, sub_addr in list(brand_versions) + config.extra_ecus: - # Only query ecus in whitelist if whitelist is not empty - if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: - a = (addr, sub_addr, r.bus) - # Build set of queries - if sub_addr is None: - if a not in parallel_queries[r.obd_multiplexing]: - parallel_queries[r.obd_multiplexing].append(a) - else: # subaddresses must be queried one by one - if [a] not in queries[r.obd_multiplexing]: - queries[r.obd_multiplexing].append([a]) - - # Build set of expected responses to filter - response_addr = uds.get_rx_addr_for_tx_addr(addr, r.rx_offset) - responses.add((response_addr, sub_addr, r.bus)) + for ecu_type, addr, sub_addr in config.get_all_ecus(VERSIONS[brand]): + # Only query ecus in whitelist if whitelist is not empty + if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: + a = (addr, sub_addr, r.bus) + # Build set of queries + if sub_addr is None: + if a not in parallel_queries[r.obd_multiplexing]: + parallel_queries[r.obd_multiplexing].append(a) + else: # subaddresses must be queried one by one + if [a] not in queries[r.obd_multiplexing]: + queries[r.obd_multiplexing].append([a]) + + # Build set of expected responses to filter + response_addr = uds.get_rx_addr_for_tx_addr(addr, r.rx_offset) + responses.add((response_addr, sub_addr, r.bus)) for obd_multiplexing in queries: queries[obd_multiplexing].insert(0, parallel_queries[obd_multiplexing]) @@ -207,11 +203,12 @@ def get_present_ecus(logcan, sendcan, num_pandas=1) -> Set[EcuAddrBusType]: return ecu_responses -def get_brand_ecu_matches(ecu_rx_addrs): +def get_brand_ecu_matches(ecu_rx_addrs: Set[EcuAddrBusType]) -> dict[str, set[AddrType]]: """Returns dictionary of brands and matches with ECUs in their FW versions""" - brand_addrs = get_brand_addrs() - brand_matches = {brand: set() for brand, _, _ in REQUESTS} + brand_addrs = {brand: {(addr, subaddr) for _, addr, subaddr in config.get_all_ecus(VERSIONS[brand])} for + brand, config in FW_QUERY_CONFIGS.items()} + brand_matches: dict[str, set[AddrType]] = {brand: set() for brand, _, _ in REQUESTS} brand_rx_offsets = {(brand, r.rx_offset) for brand, _, r in REQUESTS} for addr, sub_addr, _ in ecu_rx_addrs: @@ -275,27 +272,25 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, for brand, brand_versions in versions.items(): config = FW_QUERY_CONFIGS[brand] - for ecu in brand_versions.values(): - # Each brand can define extra ECUs to query for data collection - for ecu_type, addr, sub_addr in list(ecu) + config.extra_ecus: - a = (brand, addr, sub_addr) - if a not in ecu_types: - ecu_types[a] = ecu_type - - if sub_addr is None: - if a not in parallel_addrs: - parallel_addrs.append(a) - else: - if [a] not in addrs: - addrs.append([a]) + for ecu_type, addr, sub_addr in config.get_all_ecus(brand_versions): + a = (brand, addr, sub_addr) + if a not in ecu_types: + ecu_types[a] = ecu_type + + if sub_addr is None: + if a not in parallel_addrs: + parallel_addrs.append(a) + else: + if [a] not in addrs: + addrs.append([a]) addrs.insert(0, parallel_addrs) # Get versions and build capnp list to put into CarParams car_fw = [] requests = [(brand, config, r) for brand, config, r in REQUESTS if is_brand(brand, query_brand)] - for addr in tqdm(addrs, disable=not progress): - for addr_chunk in chunks(addr): + for addr_group in tqdm(addrs, disable=not progress): # split by subaddr, if any + for addr_chunk in chunks(addr_group): for brand, config, r in requests: # Skip query if no panda available if r.bus > num_pandas * 4 - 1: @@ -350,6 +345,13 @@ if __name__ == "__main__": pandaStates_sock = messaging.sub_sock('pandaStates') sendcan = messaging.pub_sock('sendcan') + # Set up params for boardd + params = Params() + params.remove("FirmwareQueryDone") + params.put_bool("IsOnroad", False) + time.sleep(0.2) # thread is 10 Hz + params.put_bool("IsOnroad", True) + extra: Any = None if args.scan: extra = {} @@ -360,13 +362,12 @@ if __name__ == "__main__": extra[(Ecu.unknown, 0x750, i)] = [] extra = {"any": {"debug": extra}} - time.sleep(1.) num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates) t = time.time() print("Getting vin...") - vin_rx_addr, vin = get_vin(logcan, sendcan, 1, retry=10, debug=args.debug) - print(f'RX: {hex(vin_rx_addr)}, VIN: {vin}') + vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (0, 1), retry=10, debug=args.debug) + print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') print(f"Getting VIN took {time.time() - t:.3f} s") print() diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index f51cb75372..6c7e8007f2 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -154,21 +154,6 @@ class CarController: if self.frame % 10 == 0: can_sends.append(gmcan.create_pscm_status(self.packer_pt, CanBus.CAMERA, CS.pscm_status)) - # Show green icon when LKA torque is applied, and - # alarming orange icon when approaching torque limit. - # If not sent again, LKA icon disappears in about 5 seconds. - # Conveniently, sending camera message periodically also works as a keepalive. - lka_active = CS.lkas_status == 1 - lka_critical = lka_active and abs(actuators.steer) > 0.9 - lka_icon_status = (lka_active, lka_critical) - - # SW_GMLAN not yet on cam harness, no HUD alerts - if self.CP.networkLocation != NetworkLocation.fwdCamera and \ - (self.frame % self.params.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last): - steer_alert = hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw) - can_sends.append(gmcan.create_lka_icon_command(CanBus.SW_GMLAN, lka_active, lka_critical, steer_alert)) - self.lka_icon_status_last = lka_icon_status - new_actuators = actuators.copy() new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX new_actuators.steerOutputCan = self.apply_steer_last diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 89c1a3596a..c3d061de78 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -33,7 +33,9 @@ class CarState(CarStateBase): self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) - self.moving_backward = pt_cp.vl["EBCMWheelSpdRear"]["MovingBackward"] != 0 + # This is to avoid a fault where you engage while still moving backwards after shifting to D. + # An Equinox has been seen with an unsupported status (3), so only check if either wheel is in reverse (2) + self.moving_backward = (pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2) or (pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2) # Variables used for avoiding LKAS faults self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 @@ -113,6 +115,10 @@ class CarState(CarStateBase): if self.CP.pcmCruise: ret.cruiseState.nonAdaptive = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCCruiseState"] not in (2, 3) + if self.CP.enableBsm: + ret.leftBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["LeftBSM"] == 1 + ret.rightBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["RightBSM"] == 1 + return ret @staticmethod @@ -146,6 +152,9 @@ class CarState(CarStateBase): ("ECMAcceleratorPos", 80), ] + if CP.enableBsm: + messages.append(("BCMBlindSpotMonitor", 10)) + # Used to read back last counter sent to PT by camera if CP.networkLocation == NetworkLocation.fwdCamera: messages += [ diff --git a/selfdrive/car/gm/fingerprints.py b/selfdrive/car/gm/fingerprints.py new file mode 100644 index 0000000000..73a205a250 --- /dev/null +++ b/selfdrive/car/gm/fingerprints.py @@ -0,0 +1,63 @@ +# ruff: noqa: E501 +from openpilot.selfdrive.car.gm.values import CAR + +# Trailblazer also matches as a SILVERADO, TODO: split with fw versions +# FIXME: There are Equinox users with different message lengths, specifically 304 and 320 + + +FINGERPRINTS = { + CAR.HOLDEN_ASTRA: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7 + }], + CAR.VOLT: [{ + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }, + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 + }, + { + 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 + }], + CAR.BUICK_LACROSSE: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 + }], + CAR.BUICK_REGAL: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 + }], + CAR.CADILLAC_ATS: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.MALIBU: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.ACADIA: [{ + 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 + }, + { + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.ESCALADE: [{ + 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 + }], + CAR.ESCALADE_ESV: [{ + 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 + }], + CAR.ESCALADE_ESV_2019: [{ + 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 + }], + CAR.BOLT_EUV: [{ + 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }], + CAR.SILVERADO: [{ + 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }], + CAR.EQUINOX: [{ + 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }, + { + 190: 6, 201: 8, 211: 2, 717: 5, 241: 6, 451: 8, 298: 8, 452: 8, 453: 6, 479: 3, 485: 8, 249: 8, 500: 6, 587: 8, 1611: 8, 289: 8, 481: 7, 193: 8, 197: 8, 209: 7, 455: 7, 489: 8, 309: 8, 413: 8, 501: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 311: 8, 510: 8, 528: 5, 532: 6, 715: 8, 560: 8, 562: 8, 707: 8, 789: 5, 869: 4, 880: 6, 761: 7, 840: 5, 842: 5, 844: 8, 313: 8, 381: 8, 386: 8, 810: 8, 322: 7, 384: 4, 800: 6, 1033: 7, 1034: 7, 1296: 4, 753: 5, 388: 8, 288: 5, 497: 8, 463: 3, 304: 3, 977: 8, 1001: 8, 1280: 4, 320: 4, 352: 5, 563: 5, 565: 5, 1221: 5, 1011: 6, 1017: 8, 1020: 8, 1249: 8, 1300: 8, 328: 1, 1217: 8, 1233: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1930: 7, 1271: 8 + }], +} + +FW_VERSIONS: dict[str, dict[tuple, list[bytes]]] = { +} diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index a0defb7cfb..05caa28510 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -1,13 +1,15 @@ #!/usr/bin/env python3 +import os from cereal import car from math import fabs, exp from panda import Panda +from openpilot.common.basedir import BASEDIR from openpilot.common.conversions import Conversions as CV from openpilot.selfdrive.car import create_button_events, get_safety_config from openpilot.selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG from openpilot.selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus -from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD +from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel from openpilot.selfdrive.controls.lib.drive_helpers import get_friction ButtonType = car.CarState.ButtonEvent.Type @@ -25,6 +27,8 @@ NON_LINEAR_TORQUE_PARAMS = { CAR.SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] } +NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_weights.json') + class CarInterface(CarInterfaceBase): @staticmethod @@ -44,8 +48,8 @@ class CarInterface(CarInterfaceBase): else: return CarInterfaceBase.get_steer_feedforward_default - def torque_from_lateral_accel_siglin(self, lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: + def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, + lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) def sig(val): @@ -58,11 +62,22 @@ class CarInterface(CarInterfaceBase): non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) assert non_linear_torque_params, "The params are not defined" a, b, c, _ = non_linear_torque_params - steer_torque = (sig(lateral_accel_value * a) * b) + (lateral_accel_value * c) + steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) return float(steer_torque) + friction + def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, + lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + inputs = list(latcontrol_inputs) + if gravity_adjusted: + inputs[0] += inputs[1] + return float(self.neural_ff_model.predict(inputs)) + friction + def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - if self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: + if self.CP.carFingerprint == CAR.BOLT_EUV: + self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) + return self.torque_from_lateral_accel_neural + elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: return self.torque_from_lateral_accel_siglin else: return self.torque_from_lateral_accel_linear @@ -72,6 +87,7 @@ class CarInterface(CarInterfaceBase): ret.carName = "gm" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] ret.autoResumeSng = False + ret.enableBsm = 0x142 in fingerprint[CanBus.POWERTRAIN] if candidate in EV_CAR: ret.transmissionType = TransmissionType.direct @@ -121,7 +137,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX} or \ + ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL} or \ (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable) # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index e9ec8de9c5..8188ad4e6e 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -1,4 +1,3 @@ -# ruff: noqa: E501 from collections import defaultdict from dataclasses import dataclass from enum import Enum, StrEnum @@ -7,6 +6,8 @@ from typing import Dict, List, Union from cereal import car from openpilot.selfdrive.car import dbc_dict from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarInfo, CarParts, Column +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + Ecu = car.CarParams.Ecu @@ -140,92 +141,46 @@ class CanBus: OBSTACLE = 1 CAMERA = 2 CHASSIS = 2 - SW_GMLAN = 3 LOOPBACK = 128 DROPPED = 192 -FINGERPRINTS = { - CAR.HOLDEN_ASTRA: [ - # Astra BK MY17, ASCM unplugged - { - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7, - }], - CAR.VOLT: [ - # Volt Premier w/ ACC 2017 - { - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 - }, - # Volt Premier w/ ACC 2018 - { - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 - }, - # Volt Premier 2018 w/ flashed firmware, no radar - { - 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 - }], - CAR.BUICK_LACROSSE: [ - # LaCrosse Premium AWD 2017 - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.BUICK_REGAL : [ - # Regal TourX Essence w/ ACC 2018 - { - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 - }], - CAR.CADILLAC_ATS: [ - # Cadillac ATS Coupe Premium Performance 3.6L RWD w/ ACC 2018 - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.MALIBU: [ - # Malibu Premier w/ ACC 2017 - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8, - }], - CAR.ACADIA: [ - # Acadia Denali w/ACC 2018 - { - 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 - }, - # Acadia Denali w/ /ACC 2018 - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.ESCALADE: [ - { - 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.ESCALADE_ESV: [ - { - 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 - }], - CAR.ESCALADE_ESV_2019: [ - { - 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 - }], - CAR.BOLT_EUV: [ - { - 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.SILVERADO: [ - { - 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.EQUINOX: [ - { - 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - # Trailblazer also matches as a Silverado, so comment out to avoid conflicts. - # TODO: split with FW versions - # CAR.TRAILBLAZER: [ - # { - # 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1609: 8, 1611: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8 - # }], -} + +# In a Data Module, an identifier is a string used to recognize an object, +# either by itself or together with the identifiers of parent objects. +# Each returns a 4 byte hex representation of the decimal part number. `b"\x02\x8c\xf0'"` -> 42790951 +GM_SOFTWARE_MODULE_1_REQUEST = b'\x1a\xc1' +GM_SOFTWARE_MODULE_2_REQUEST = b'\x1a\xc2' +GM_SOFTWARE_MODULE_3_REQUEST = b'\x1a\xc3' +# This DID is for identifying the part number that reflects the mix of hardware, +# software, and calibrations in the ECU when it first arrives at the vehicle assembly plant. +# If there's an Alpha Code, it's associated with this part number and stored in the DID $DB. +GM_END_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcb' +GM_BASE_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcc' +GM_FW_RESPONSE = b'\x5a' + +GM_FW_REQUESTS = [ + GM_SOFTWARE_MODULE_1_REQUEST, + GM_SOFTWARE_MODULE_2_REQUEST, + GM_SOFTWARE_MODULE_3_REQUEST, + GM_END_MODEL_PART_NUMBER_REQUEST, + GM_BASE_MODEL_PART_NUMBER_REQUEST, +] GM_RX_OFFSET = 0x400 +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for req in GM_FW_REQUESTS for request in [ + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, req], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, GM_FW_RESPONSE + bytes([req[-1]])], + rx_offset=GM_RX_OFFSET, + bus=0, + logging=True, + ), + ]], + extra_ecus=[(Ecu.fwdCamera, 0x24b, None)], +) + DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) EV_CAR = {CAR.VOLT, CAR.BOLT_EUV} diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 03aedb31d2..9025f72397 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -7,8 +7,8 @@ from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from openpilot.selfdrive.car.honda.hondacan import get_cruise_speed_conversion, get_pt_bus from openpilot.selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL, \ - HONDA_BOSCH_RADARLESS + HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ + HondaFlags from openpilot.selfdrive.car.interfaces import CarStateBase TransmissionType = car.CarParams.TransmissionType @@ -44,7 +44,7 @@ def get_can_messages(CP, gearbox_msg): else: messages.append((gearbox_msg, 100)) - if CP.carFingerprint in HONDA_BOSCH_ALT_BRAKE_SIGNAL: + if CP.flags & HondaFlags.BOSCH_ALT_BRAKE: messages.append(("BRAKE_MODULE", 50)) if CP.carFingerprint in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN}): @@ -217,7 +217,7 @@ class CarState(CarStateBase): else: ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS - if self.CP.carFingerprint in HONDA_BOSCH_ALT_BRAKE_SIGNAL: + if self.CP.flags & HondaFlags.BOSCH_ALT_BRAKE: ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 else: # brake switch has shown some single time step noise, so only considered when diff --git a/selfdrive/car/honda/fingerprints.py b/selfdrive/car/honda/fingerprints.py new file mode 100644 index 0000000000..359ae83b15 --- /dev/null +++ b/selfdrive/car/honda/fingerprints.py @@ -0,0 +1,1436 @@ +from cereal import car +from openpilot.selfdrive.car.honda.values import CAR + +Ecu = car.CarParams.Ecu + +# Modified FW can be identified by the second dash being replaced by a comma +# For example: `b'39990-TVA,A150\x00\x00'` +# +# TODO: vsa is "essential" for fpv2 but doesn't appear on some CAR.FREED models + + +FW_VERSIONS = { + CAR.ACCORD: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-6A0-8720\x00\x00', + b'37805-6A0-9520\x00\x00', + b'37805-6A0-9620\x00\x00', + b'37805-6A0-9720\x00\x00', + b'37805-6A0-A540\x00\x00', + b'37805-6A0-A550\x00\x00', + b'37805-6A0-A640\x00\x00', + b'37805-6A0-A650\x00\x00', + b'37805-6A0-A740\x00\x00', + b'37805-6A0-A750\x00\x00', + b'37805-6A0-A840\x00\x00', + b'37805-6A0-A850\x00\x00', + b'37805-6A0-A930\x00\x00', + b'37805-6A0-AF30\x00\x00', + b'37805-6A0-AG30\x00\x00', + b'37805-6A0-AJ10\x00\x00', + b'37805-6A0-C540\x00\x00', + b'37805-6A0-CG20\x00\x00', + b'37805-6A1-H650\x00\x00', + b'37805-6B2-A550\x00\x00', + b'37805-6B2-A560\x00\x00', + b'37805-6B2-A650\x00\x00', + b'37805-6B2-A660\x00\x00', + b'37805-6B2-A720\x00\x00', + b'37805-6B2-A810\x00\x00', + b'37805-6B2-A820\x00\x00', + b'37805-6B2-A920\x00\x00', + b'37805-6B2-AA10\x00\x00', + b'37805-6B2-C520\x00\x00', + b'37805-6B2-C540\x00\x00', + b'37805-6B2-M520\x00\x00', + b'37805-6B2-Y810\x00\x00', + b'37805-6M4-B730\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TVC-A910\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-6A7-A220\x00\x00', + b'28101-6A7-A230\x00\x00', + b'28101-6A7-A320\x00\x00', + b'28101-6A7-A330\x00\x00', + b'28101-6A7-A410\x00\x00', + b'28101-6A7-A510\x00\x00', + b'28101-6A7-A610\x00\x00', + b'28101-6A7-A710\x00\x00', + b'28101-6A9-H140\x00\x00', + b'28101-6A9-H420\x00\x00', + b'28102-6B8-A560\x00\x00', + b'28102-6B8-A570\x00\x00', + b'28102-6B8-A700\x00\x00', + b'28102-6B8-A800\x00\x00', + b'28102-6B8-C560\x00\x00', + b'28102-6B8-C570\x00\x00', + b'28102-6B8-M520\x00\x00', + b'28102-6B8-R700\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TVA-A050\x00\x00', + b'46114-TVA-A060\x00\x00', + b'46114-TVA-A080\x00\x00', + b'46114-TVA-A120\x00\x00', + b'46114-TVA-A320\x00\x00', + b'46114-TVE-H550\x00\x00', + b'46114-TVE-H560\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TVA-B040\x00\x00', + b'57114-TVA-B050\x00\x00', + b'57114-TVA-B060\x00\x00', + b'57114-TVA-B530\x00\x00', + b'57114-TVA-C040\x00\x00', + b'57114-TVA-C050\x00\x00', + b'57114-TVA-C060\x00\x00', + b'57114-TVA-C530\x00\x00', + b'57114-TVA-E520\x00\x00', + b'57114-TVE-H250\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBX-H120\x00\x00', + b'39990-TVA,A150\x00\x00', + b'39990-TVA-A140\x00\x00', + b'39990-TVA-A150\x00\x00', + b'39990-TVA-A160\x00\x00', + b'39990-TVA-A340\x00\x00', + b'39990-TVA-X030\x00\x00', + b'39990-TVA-X040\x00\x00', + b'39990-TVE-H130\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBX-H230\x00\x00', + b'77959-TVA-A460\x00\x00', + b'77959-TVA-F330\x00\x00', + b'77959-TVA-H230\x00\x00', + b'77959-TVA-L420\x00\x00', + b'77959-TVA-X330\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TBX-H310\x00\x00', + b'78109-TVA-A010\x00\x00', + b'78109-TVA-A020\x00\x00', + b'78109-TVA-A030\x00\x00', + b'78109-TVA-A110\x00\x00', + b'78109-TVA-A120\x00\x00', + b'78109-TVA-A130\x00\x00', + b'78109-TVA-A210\x00\x00', + b'78109-TVA-A220\x00\x00', + b'78109-TVA-A230\x00\x00', + b'78109-TVA-A310\x00\x00', + b'78109-TVA-C010\x00\x00', + b'78109-TVA-C130\x00\x00', + b'78109-TVA-L010\x00\x00', + b'78109-TVA-L210\x00\x00', + b'78109-TVA-R310\x00\x00', + b'78109-TVC-A010\x00\x00', + b'78109-TVC-A020\x00\x00', + b'78109-TVC-A030\x00\x00', + b'78109-TVC-A110\x00\x00', + b'78109-TVC-A130\x00\x00', + b'78109-TVC-A210\x00\x00', + b'78109-TVC-A220\x00\x00', + b'78109-TVC-A230\x00\x00', + b'78109-TVC-C010\x00\x00', + b'78109-TVC-C110\x00\x00', + b'78109-TVC-L010\x00\x00', + b'78109-TVC-L210\x00\x00', + b'78109-TVC-M510\x00\x00', + b'78109-TVC-YF10\x00\x00', + b'78109-TVE-H610\x00\x00', + b'78109-TWA-A210\x00\x00', + ], + (Ecu.hud, 0x18da61f1, None): [ + b'78209-TVA-A010\x00\x00', + b'78209-TVA-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TBX-H140\x00\x00', + b'36802-TVA-A150\x00\x00', + b'36802-TVA-A160\x00\x00', + b'36802-TVA-A170\x00\x00', + b'36802-TVA-A180\x00\x00', + b'36802-TVA-A330\x00\x00', + b'36802-TVC-A330\x00\x00', + b'36802-TVE-H070\x00\x00', + b'36802-TWA-A070\x00\x00', + b'36802-TWA-A080\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TBX-H130\x00\x00', + b'36161-TVA-A060\x00\x00', + b'36161-TVA-A330\x00\x00', + b'36161-TVC-A330\x00\x00', + b'36161-TVE-H050\x00\x00', + b'36161-TWA-A070\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TVA-A010\x00\x00', + b'38897-TVA-A020\x00\x00', + b'38897-TVA-A230\x00\x00', + b'38897-TVA-A240\x00\x00', + ], + }, + CAR.ACCORDH: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TWA-A120\x00\x00', + b'38897-TWD-J020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TWA-A040\x00\x00', + b'57114-TWA-A050\x00\x00', + b'57114-TWA-A530\x00\x00', + b'57114-TWA-B520\x00\x00', + b'57114-TWA-C510\x00\x00', + b'57114-TWB-H030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TWA-A440\x00\x00', + b'77959-TWA-L420\x00\x00', + b'77959-TWB-H220\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TWA-A010\x00\x00', + b'78109-TWA-A020\x00\x00', + b'78109-TWA-A030\x00\x00', + b'78109-TWA-A110\x00\x00', + b'78109-TWA-A120\x00\x00', + b'78109-TWA-A130\x00\x00', + b'78109-TWA-A210\x00\x00', + b'78109-TWA-A220\x00\x00', + b'78109-TWA-A230\x00\x00', + b'78109-TWA-A610\x00\x00', + b'78109-TWA-H210\x00\x00', + b'78109-TWA-L010\x00\x00', + b'78109-TWA-L210\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.hud, 0x18da61f1, None): [ + b'78209-TVA-A010\x00\x00', + b'78209-TVA-A110\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TWA-A070\x00\x00', + b'36161-TWA-A330\x00\x00', + b'36161-TWB-H040\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TWA-A070\x00\x00', + b'36802-TWA-A080\x00\x00', + b'36802-TWA-A210\x00\x00', + b'36802-TWA-A330\x00\x00', + b'36802-TWB-H060\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TVA-A150\x00\x00', + b'39990-TVA-A160\x00\x00', + b'39990-TVA-A340\x00\x00', + b'39990-TWB-H120\x00\x00', + ], + }, + CAR.CIVIC: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5AA-A640\x00\x00', + b'37805-5AA-A650\x00\x00', + b'37805-5AA-A670\x00\x00', + b'37805-5AA-A680\x00\x00', + b'37805-5AA-A810\x00\x00', + b'37805-5AA-C640\x00\x00', + b'37805-5AA-C680\x00\x00', + b'37805-5AA-C820\x00\x00', + b'37805-5AA-L650\x00\x00', + b'37805-5AA-L660\x00\x00', + b'37805-5AA-L680\x00\x00', + b'37805-5AA-L690\x00\x00', + b'37805-5AA-L810\x00\x00', + b'37805-5AG-Q710\x00\x00', + b'37805-5AJ-A610\x00\x00', + b'37805-5AJ-A620\x00\x00', + b'37805-5AJ-L610\x00\x00', + b'37805-5BA-A310\x00\x00', + b'37805-5BA-A510\x00\x00', + b'37805-5BA-A740\x00\x00', + b'37805-5BA-A760\x00\x00', + b'37805-5BA-A930\x00\x00', + b'37805-5BA-A960\x00\x00', + b'37805-5BA-C640\x00\x00', + b'37805-5BA-C860\x00\x00', + b'37805-5BA-L410\x00\x00', + b'37805-5BA-L760\x00\x00', + b'37805-5BA-L930\x00\x00', + b'37805-5BA-L940\x00\x00', + b'37805-5BA-L960\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5CG-A040\x00\x00', + b'28101-5CG-A050\x00\x00', + b'28101-5CG-A070\x00\x00', + b'28101-5CG-A080\x00\x00', + b'28101-5CG-A320\x00\x00', + b'28101-5CG-A810\x00\x00', + b'28101-5CG-A820\x00\x00', + b'28101-5DJ-A040\x00\x00', + b'28101-5DJ-A060\x00\x00', + b'28101-5DJ-A510\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBA-A540\x00\x00', + b'57114-TBA-A550\x00\x00', + b'57114-TBA-A560\x00\x00', + b'57114-TBA-A570\x00\x00', + b'57114-TEA-Q220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBA,A030\x00\x00', + b'39990-TBA-A030\x00\x00', + b'39990-TBG-A030\x00\x00', + b'39990-TEA-T020\x00\x00', + b'39990-TEG-A010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBA-A030\x00\x00', + b'77959-TBA-A040\x00\x00', + b'77959-TBG-A020\x00\x00', + b'77959-TBG-A030\x00\x00', + b'77959-TEA-Q820\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TBA-A510\x00\x00', + b'78109-TBA-A520\x00\x00', + b'78109-TBA-A530\x00\x00', + b'78109-TBA-C310\x00\x00', + b'78109-TBA-C520\x00\x00', + b'78109-TBC-A310\x00\x00', + b'78109-TBC-A320\x00\x00', + b'78109-TBC-A510\x00\x00', + b'78109-TBC-A520\x00\x00', + b'78109-TBC-A530\x00\x00', + b'78109-TBC-C510\x00\x00', + b'78109-TBC-C520\x00\x00', + b'78109-TBC-C530\x00\x00', + b'78109-TBH-A510\x00\x00', + b'78109-TBH-A530\x00\x00', + b'78109-TED-Q510\x00\x00', + b'78109-TEG-A310\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TBA-A020\x00\x00', + b'36161-TBA-A030\x00\x00', + b'36161-TBA-A040\x00\x00', + b'36161-TBC-A020\x00\x00', + b'36161-TBC-A030\x00\x00', + b'36161-TED-Q320\x00\x00', + b'36161-TEG-A010\x00\x00', + b'36161-TEG-A020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A010\x00\x00', + b'38897-TBA-A020\x00\x00', + ], + }, + CAR.CIVIC_BOSCH: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5AA-A940\x00\x00', + b'37805-5AA-A950\x00\x00', + b'37805-5AA-C950\x00\x00', + b'37805-5AA-L940\x00\x00', + b'37805-5AA-L950\x00\x00', + b'37805-5AG-Z910\x00\x00', + b'37805-5AJ-A750\x00\x00', + b'37805-5AJ-L750\x00\x00', + b'37805-5AK-T530\x00\x00', + b'37805-5AN-A750\x00\x00', + b'37805-5AN-A830\x00\x00', + b'37805-5AN-A840\x00\x00', + b'37805-5AN-A930\x00\x00', + b'37805-5AN-A940\x00\x00', + b'37805-5AN-A950\x00\x00', + b'37805-5AN-AG20\x00\x00', + b'37805-5AN-AH20\x00\x00', + b'37805-5AN-AJ30\x00\x00', + b'37805-5AN-AK10\x00\x00', + b'37805-5AN-AK20\x00\x00', + b'37805-5AN-AR10\x00\x00', + b'37805-5AN-AR20\x00\x00', + b'37805-5AN-C650\x00\x00', + b'37805-5AN-CH20\x00\x00', + b'37805-5AN-E630\x00\x00', + b'37805-5AN-E720\x00\x00', + b'37805-5AN-E820\x00\x00', + b'37805-5AN-J820\x00\x00', + b'37805-5AN-L840\x00\x00', + b'37805-5AN-L930\x00\x00', + b'37805-5AN-L940\x00\x00', + b'37805-5AN-LF20\x00\x00', + b'37805-5AN-LH20\x00\x00', + b'37805-5AN-LJ20\x00\x00', + b'37805-5AN-LR20\x00\x00', + b'37805-5AN-LS20\x00\x00', + b'37805-5AW-G720\x00\x00', + b'37805-5AZ-E850\x00\x00', + b'37805-5AZ-G540\x00\x00', + b'37805-5AZ-G740\x00\x00', + b'37805-5AZ-G840\x00\x00', + b'37805-5BB-A530\x00\x00', + b'37805-5BB-A540\x00\x00', + b'37805-5BB-A620\x00\x00', + b'37805-5BB-A630\x00\x00', + b'37805-5BB-A640\x00\x00', + b'37805-5BB-C540\x00\x00', + b'37805-5BB-C630\x00\x00', + b'37805-5BB-C640\x00\x00', + b'37805-5BB-L540\x00\x00', + b'37805-5BB-L630\x00\x00', + b'37805-5BB-L640\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5CG-A920\x00\x00', + b'28101-5CG-AB10\x00\x00', + b'28101-5CG-C110\x00\x00', + b'28101-5CG-C220\x00\x00', + b'28101-5CG-C320\x00\x00', + b'28101-5CG-G020\x00\x00', + b'28101-5CG-L020\x00\x00', + b'28101-5CK-A130\x00\x00', + b'28101-5CK-A140\x00\x00', + b'28101-5CK-A150\x00\x00', + b'28101-5CK-C130\x00\x00', + b'28101-5CK-C140\x00\x00', + b'28101-5CK-C150\x00\x00', + b'28101-5CK-G210\x00\x00', + b'28101-5CK-J710\x00\x00', + b'28101-5CK-Q610\x00\x00', + b'28101-5DJ-A610\x00\x00', + b'28101-5DJ-A710\x00\x00', + b'28101-5DV-E330\x00\x00', + b'28101-5DV-E610\x00\x00', + b'28101-5DV-E820\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBG-A330\x00\x00', + b'57114-TBG-A340\x00\x00', + b'57114-TBG-A350\x00\x00', + b'57114-TGG-A340\x00\x00', + b'57114-TGG-C320\x00\x00', + b'57114-TGG-G320\x00\x00', + b'57114-TGG-L320\x00\x00', + b'57114-TGG-L330\x00\x00', + b'57114-TGK-T320\x00\x00', + b'57114-TGL-G330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBA-C020\x00\x00', + b'39990-TBA-C120\x00\x00', + b'39990-TEA-T820\x00\x00', + b'39990-TEZ-T020\x00\x00', + b'39990-TGG,A020\x00\x00', + b'39990-TGG,A120\x00\x00', + b'39990-TGG-A020\x00\x00', + b'39990-TGG-A120\x00\x00', + b'39990-TGG-J510\x00\x00', + b'39990-TGL-E130\x00\x00', + b'39990-TGN-E120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBA-A060\x00\x00', + b'77959-TBG-A050\x00\x00', + b'77959-TEA-G020\x00\x00', + b'77959-TGG-A020\x00\x00', + b'77959-TGG-A030\x00\x00', + b'77959-TGG-E010\x00\x00', + b'77959-TGG-G010\x00\x00', + b'77959-TGG-G110\x00\x00', + b'77959-TGG-J320\x00\x00', + b'77959-TGG-Z820\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TBA-A110\x00\x00', + b'78109-TBA-A910\x00\x00', + b'78109-TBA-C340\x00\x00', + b'78109-TBA-C910\x00\x00', + b'78109-TBC-A740\x00\x00', + b'78109-TBC-C540\x00\x00', + b'78109-TBG-A110\x00\x00', + b'78109-TBH-A710\x00\x00', + b'78109-TEG-A720\x00\x00', + b'78109-TFJ-G020\x00\x00', + b'78109-TGG-9020\x00\x00', + b'78109-TGG-A210\x00\x00', + b'78109-TGG-A220\x00\x00', + b'78109-TGG-A310\x00\x00', + b'78109-TGG-A320\x00\x00', + b'78109-TGG-A330\x00\x00', + b'78109-TGG-A610\x00\x00', + b'78109-TGG-A620\x00\x00', + b'78109-TGG-A810\x00\x00', + b'78109-TGG-A820\x00\x00', + b'78109-TGG-C010\x00\x00', + b'78109-TGG-C220\x00\x00', + b'78109-TGG-E110\x00\x00', + b'78109-TGG-G030\x00\x00', + b'78109-TGG-G230\x00\x00', + b'78109-TGG-G410\x00\x00', + b'78109-TGK-Z410\x00\x00', + b'78109-TGL-G120\x00\x00', + b'78109-TGL-G130\x00\x00', + b'78109-TGL-G210\x00\x00', + b'78109-TGL-G230\x00\x00', + b'78109-TGL-GM10\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TBA-A150\x00\x00', + b'36802-TBA-A160\x00\x00', + b'36802-TFJ-G060\x00\x00', + b'36802-TGG-A050\x00\x00', + b'36802-TGG-A060\x00\x00', + b'36802-TGG-A070\x00\x00', + b'36802-TGG-A130\x00\x00', + b'36802-TGG-G040\x00\x00', + b'36802-TGG-G130\x00\x00', + b'36802-TGK-Q120\x00\x00', + b'36802-TGL-G040\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TBA-A130\x00\x00', + b'36161-TBA-A140\x00\x00', + b'36161-TFJ-G070\x00\x00', + b'36161-TGG-A060\x00\x00', + b'36161-TGG-A080\x00\x00', + b'36161-TGG-A120\x00\x00', + b'36161-TGG-G050\x00\x00', + b'36161-TGG-G070\x00\x00', + b'36161-TGG-G130\x00\x00', + b'36161-TGG-G140\x00\x00', + b'36161-TGK-Q120\x00\x00', + b'36161-TGL-G050\x00\x00', + b'36161-TGL-G070\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A020\x00\x00', + b'38897-TBA-A110\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'39494-TGL-G030\x00\x00', + ], + }, + CAR.CIVIC_BOSCH_DIESEL: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-59N-G630\x00\x00', + b'37805-59N-G830\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-59Y-G220\x00\x00', + b'28101-59Y-G620\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TGN-E320\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TFK-G020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TFK-G210\x00\x00', + b'77959-TGN-G220\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TFK-G020\x00\x00', + b'78109-TGN-G120\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TFK-G130\x00\x00', + b'36802-TGN-G130\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TGN-E010\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TFK-G130\x00\x00', + b'36161-TGN-G130\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A020\x00\x00', + ], + }, + CAR.CRV: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T1W-A230\x00\x00', + b'57114-T1W-A240\x00\x00', + b'57114-TFF-A940\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T0A-A230\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T1W-A210\x00\x00', + b'78109-T1W-C210\x00\x00', + b'78109-T1X-A210\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T1W-A830\x00\x00', + b'36161-T1W-C830\x00\x00', + b'36161-T1X-A830\x00\x00', + ], + }, + CAR.CRV_5G: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5PA-3060\x00\x00', + b'37805-5PA-3080\x00\x00', + b'37805-5PA-3180\x00\x00', + b'37805-5PA-4050\x00\x00', + b'37805-5PA-4150\x00\x00', + b'37805-5PA-6520\x00\x00', + b'37805-5PA-6530\x00\x00', + b'37805-5PA-6630\x00\x00', + b'37805-5PA-6640\x00\x00', + b'37805-5PA-7630\x00\x00', + b'37805-5PA-9530\x00\x00', + b'37805-5PA-9630\x00\x00', + b'37805-5PA-9640\x00\x00', + b'37805-5PA-9730\x00\x00', + b'37805-5PA-9830\x00\x00', + b'37805-5PA-9840\x00\x00', + b'37805-5PA-A650\x00\x00', + b'37805-5PA-A670\x00\x00', + b'37805-5PA-A680\x00\x00', + b'37805-5PA-A850\x00\x00', + b'37805-5PA-A870\x00\x00', + b'37805-5PA-A880\x00\x00', + b'37805-5PA-A890\x00\x00', + b'37805-5PA-AB10\x00\x00', + b'37805-5PA-AD10\x00\x00', + b'37805-5PA-AF20\x00\x00', + b'37805-5PA-AH20\x00\x00', + b'37805-5PA-BF10\x00\x00', + b'37805-5PA-C680\x00\x00', + b'37805-5PD-Q630\x00\x00', + b'37805-5PF-F730\x00\x00', + b'37805-5PF-M630\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5RG-A020\x00\x00', + b'28101-5RG-A030\x00\x00', + b'28101-5RG-A040\x00\x00', + b'28101-5RG-A120\x00\x00', + b'28101-5RG-A220\x00\x00', + b'28101-5RH-A020\x00\x00', + b'28101-5RH-A030\x00\x00', + b'28101-5RH-A040\x00\x00', + b'28101-5RH-A120\x00\x00', + b'28101-5RH-A220\x00\x00', + b'28101-5RL-Q010\x00\x00', + b'28101-5RM-F010\x00\x00', + b'28101-5RM-K010\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TLA-A040\x00\x00', + b'57114-TLA-A050\x00\x00', + b'57114-TLA-A060\x00\x00', + b'57114-TLB-A830\x00\x00', + b'57114-TMC-Z040\x00\x00', + b'57114-TMC-Z050\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TLA,A040\x00\x00', + b'39990-TLA-A040\x00\x00', + b'39990-TLA-A110\x00\x00', + b'39990-TLA-A220\x00\x00', + b'39990-TME-T030\x00\x00', + b'39990-TME-T120\x00\x00', + b'39990-TMT-T010\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TLA-A040\x00\x00', + b'46114-TLA-A050\x00\x00', + b'46114-TLA-A930\x00\x00', + b'46114-TMC-U020\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TLA-A020\x00\x00', + b'78109-TLA-A110\x00\x00', + b'78109-TLA-A120\x00\x00', + b'78109-TLA-A210\x00\x00', + b'78109-TLA-A220\x00\x00', + b'78109-TLA-C020\x00\x00', + b'78109-TLA-C110\x00\x00', + b'78109-TLA-C210\x00\x00', + b'78109-TLA-C310\x00\x00', + b'78109-TLB-A020\x00\x00', + b'78109-TLB-A110\x00\x00', + b'78109-TLB-A120\x00\x00', + b'78109-TLB-A210\x00\x00', + b'78109-TLB-A220\x00\x00', + b'78109-TMC-Q210\x00\x00', + b'78109-TMM-F210\x00\x00', + b'78109-TMM-M110\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TLA-A010\x00\x00', + b'38897-TLA-A110\x00\x00', + b'38897-TNY-G010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TLA-A040\x00\x00', + b'36802-TLA-A050\x00\x00', + b'36802-TLA-A060\x00\x00', + b'36802-TLA-A070\x00\x00', + b'36802-TMC-Q040\x00\x00', + b'36802-TMC-Q070\x00\x00', + b'36802-TNY-A030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TLA-A060\x00\x00', + b'36161-TLA-A070\x00\x00', + b'36161-TLA-A080\x00\x00', + b'36161-TMC-Q020\x00\x00', + b'36161-TMC-Q030\x00\x00', + b'36161-TMC-Q040\x00\x00', + b'36161-TNY-A020\x00\x00', + b'36161-TNY-A030\x00\x00', + b'36161-TNY-A040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TLA-A240\x00\x00', + b'77959-TLA-A250\x00\x00', + b'77959-TLA-A320\x00\x00', + b'77959-TLA-A410\x00\x00', + b'77959-TLA-A420\x00\x00', + b'77959-TLA-Q040\x00\x00', + b'77959-TLA-Z040\x00\x00', + b'77959-TMM-F040\x00\x00', + ], + }, + CAR.CRV_EU: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-R5Z-G740\x00\x00', + b'37805-R5Z-G780\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T1V-G920\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T1V-G520\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-T1V-G010\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5LH-E120\x00\x00', + b'28103-5LH-E100\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T1B-3050\x00\x00', + b'78109-T1V-G020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T1G-G940\x00\x00', + ], + }, + CAR.CRV_HYBRID: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TMB-H030\x00\x00', + b'57114-TPA-G020\x00\x00', + b'57114-TPG-A020\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TMA-H020\x00\x00', + b'39990-TPA-G030\x00\x00', + b'39990-TPG-A020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TMA-H110\x00\x00', + b'38897-TPG-A110\x00\x00', + b'38897-TPG-A210\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TMB-H510\x00\x00', + b'54008-TMB-H610\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TMB-H040\x00\x00', + b'36161-TPA-E050\x00\x00', + b'36161-TPG-A030\x00\x00', + b'36161-TPG-A040\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TMB-H220\x00\x00', + b'78109-TPA-G520\x00\x00', + b'78109-TPG-A110\x00\x00', + b'78109-TPG-A210\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TMB-H040\x00\x00', + b'36802-TPA-E040\x00\x00', + b'36802-TPG-A020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TLA-C320\x00\x00', + b'77959-TLA-C410\x00\x00', + b'77959-TLA-C420\x00\x00', + b'77959-TLA-G220\x00\x00', + b'77959-TLA-H240\x00\x00', + ], + }, + CAR.FIT: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T5R-L020\x00\x00', + b'57114-T5R-L220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T5R-C020\x00\x00', + b'39990-T5R-C030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T5A-J010\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T5A-A210\x00\x00', + b'78109-T5A-A410\x00\x00', + b'78109-T5A-A420\x00\x00', + b'78109-T5A-A910\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T5R-A040\x00\x00', + b'36161-T5R-A240\x00\x00', + b'36161-T5R-A520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T5R-A230\x00\x00', + ], + }, + CAR.FREED: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TDK-J010\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TDK-J050\x00\x00', + b'39990-TDK-N020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TDK-J120\x00\x00', + b'57114-TDK-J330\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TDK-J310\x00\x00', + b'78109-TDK-J320\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TDK-J070\x00\x00', + b'36161-TDK-J080\x00\x00', + b'36161-TDK-J530\x00\x00', + ], + }, + CAR.ODYSSEY: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-THR-A010\x00\x00', + b'38897-THR-A020\x00\x00', + ], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5MR-3050\x00\x00', + b'37805-5MR-3250\x00\x00', + b'37805-5MR-4070\x00\x00', + b'37805-5MR-4080\x00\x00', + b'37805-5MR-4180\x00\x00', + b'37805-5MR-A240\x00\x00', + b'37805-5MR-A250\x00\x00', + b'37805-5MR-A310\x00\x00', + b'37805-5MR-A740\x00\x00', + b'37805-5MR-A750\x00\x00', + b'37805-5MR-A840\x00\x00', + b'37805-5MR-C620\x00\x00', + b'37805-5MR-D530\x00\x00', + b'37805-5MR-K730\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-THR-A020\x00\x00', + b'39990-THR-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-THR-A010\x00\x00', + b'77959-THR-A110\x00\x00', + b'77959-THR-X010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-THR-A020\x00\x00', + b'36161-THR-A030\x00\x00', + b'36161-THR-A110\x00\x00', + b'36161-THR-A720\x00\x00', + b'36161-THR-A730\x00\x00', + b'36161-THR-A810\x00\x00', + b'36161-THR-A910\x00\x00', + b'36161-THR-C010\x00\x00', + b'36161-THR-D110\x00\x00', + b'36161-THR-K020\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5NZ-A110\x00\x00', + b'28101-5NZ-A310\x00\x00', + b'28101-5NZ-C310\x00\x00', + b'28102-5MX-A001\x00\x00', + b'28102-5MX-A600\x00\x00', + b'28102-5MX-A610\x00\x00', + b'28102-5MX-A700\x00\x00', + b'28102-5MX-A710\x00\x00', + b'28102-5MX-A900\x00\x00', + b'28102-5MX-A910\x00\x00', + b'28102-5MX-C001\x00\x00', + b'28102-5MX-C910\x00\x00', + b'28102-5MX-D001\x00\x00', + b'28102-5MX-D710\x00\x00', + b'28102-5MX-K610\x00\x00', + b'28103-5NZ-A100\x00\x00', + b'28103-5NZ-A300\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-THR-A040\x00\x00', + b'57114-THR-A110\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-THR-A220\x00\x00', + b'78109-THR-A230\x00\x00', + b'78109-THR-A420\x00\x00', + b'78109-THR-A430\x00\x00', + b'78109-THR-A720\x00\x00', + b'78109-THR-A730\x00\x00', + b'78109-THR-A820\x00\x00', + b'78109-THR-A830\x00\x00', + b'78109-THR-AB20\x00\x00', + b'78109-THR-AB30\x00\x00', + b'78109-THR-AB40\x00\x00', + b'78109-THR-AC20\x00\x00', + b'78109-THR-AC30\x00\x00', + b'78109-THR-AC40\x00\x00', + b'78109-THR-AC50\x00\x00', + b'78109-THR-AD30\x00\x00', + b'78109-THR-AE20\x00\x00', + b'78109-THR-AE30\x00\x00', + b'78109-THR-AE40\x00\x00', + b'78109-THR-AK10\x00\x00', + b'78109-THR-AL10\x00\x00', + b'78109-THR-AN10\x00\x00', + b'78109-THR-C220\x00\x00', + b'78109-THR-C320\x00\x00', + b'78109-THR-C330\x00\x00', + b'78109-THR-CE20\x00\x00', + b'78109-THR-CL10\x00\x00', + b'78109-THR-DA20\x00\x00', + b'78109-THR-DA30\x00\x00', + b'78109-THR-DA40\x00\x00', + b'78109-THR-K120\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-THR-A020\x00\x00', + ], + }, + CAR.ODYSSEY_CHN: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6D-H220\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6A-J010\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T6A-F310\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6A-P040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6A-P110\x00\x00', + ], + }, + CAR.PILOT: { + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TG7-A520\x00\x00', + b'54008-TG7-A530\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5EY-A050\x00\x00', + b'28101-5EY-A100\x00\x00', + b'28101-5EY-A430\x00\x00', + b'28101-5EY-A500\x00\x00', + b'28101-5EZ-A050\x00\x00', + b'28101-5EZ-A060\x00\x00', + b'28101-5EZ-A100\x00\x00', + b'28101-5EZ-A210\x00\x00', + b'28101-5EZ-A330\x00\x00', + b'28101-5EZ-A430\x00\x00', + b'28101-5EZ-A500\x00\x00', + b'28101-5EZ-A600\x00\x00', + b'28101-5EZ-A700\x00\x00', + b'28103-5EY-A110\x00\x00', + ], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-RLV-4060\x00\x00', + b'37805-RLV-4070\x00\x00', + b'37805-RLV-5140\x00\x00', + b'37805-RLV-5230\x00\x00', + b'37805-RLV-A830\x00\x00', + b'37805-RLV-A840\x00\x00', + b'37805-RLV-B210\x00\x00', + b'37805-RLV-B220\x00\x00', + b'37805-RLV-B420\x00\x00', + b'37805-RLV-B430\x00\x00', + b'37805-RLV-B620\x00\x00', + b'37805-RLV-B710\x00\x00', + b'37805-RLV-B720\x00\x00', + b'37805-RLV-C430\x00\x00', + b'37805-RLV-C510\x00\x00', + b'37805-RLV-C520\x00\x00', + b'37805-RLV-C530\x00\x00', + b'37805-RLV-C910\x00\x00', + b'37805-RLV-F120\x00\x00', + b'37805-RLV-L080\x00\x00', + b'37805-RLV-L090\x00\x00', + b'37805-RLV-L150\x00\x00', + b'37805-RLV-L160\x00\x00', + b'37805-RLV-L180\x00\x00', + b'37805-RLV-L350\x00\x00', + b'37805-RLV-L410\x00\x00', + b'37805-RLV-L430\x00\x00', + b'37805-RLV-L850\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TG7-A030\x00\x00', + b'38897-TG7-A040\x00\x00', + b'38897-TG7-A110\x00\x00', + b'38897-TG7-A210\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TG7-A030\x00\x00', + b'39990-TG7-A040\x00\x00', + b'39990-TG7-A060\x00\x00', + b'39990-TG7-A070\x00\x00', + b'39990-TGS-A230\x00\x00', + b'39990-TGS-A320\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TG7-A310\x00\x00', + b'36161-TG7-A520\x00\x00', + b'36161-TG7-A630\x00\x00', + b'36161-TG7-A720\x00\x00', + b'36161-TG7-A820\x00\x00', + b'36161-TG7-A930\x00\x00', + b'36161-TG7-C520\x00\x00', + b'36161-TG7-D520\x00\x00', + b'36161-TG7-D630\x00\x00', + b'36161-TG7-Y630\x00\x00', + b'36161-TG8-A410\x00\x00', + b'36161-TG8-A520\x00\x00', + b'36161-TG8-A630\x00\x00', + b'36161-TG8-A720\x00\x00', + b'36161-TG8-A830\x00\x00', + b'36161-TGS-A030\x00\x00', + b'36161-TGS-A130\x00\x00', + b'36161-TGS-A220\x00\x00', + b'36161-TGS-A320\x00\x00', + b'36161-TGT-A030\x00\x00', + b'36161-TGT-A130\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TG7-A020\x00\x00', + b'77959-TG7-A110\x00\x00', + b'77959-TG7-A210\x00\x00', + b'77959-TG7-Y210\x00\x00', + b'77959-TGS-A010\x00\x00', + b'77959-TGS-A110\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TG7-A040\x00\x00', + b'78109-TG7-A050\x00\x00', + b'78109-TG7-A420\x00\x00', + b'78109-TG7-A520\x00\x00', + b'78109-TG7-A720\x00\x00', + b'78109-TG7-AJ10\x00\x00', + b'78109-TG7-AJ20\x00\x00', + b'78109-TG7-AK10\x00\x00', + b'78109-TG7-AK20\x00\x00', + b'78109-TG7-AM20\x00\x00', + b'78109-TG7-AP10\x00\x00', + b'78109-TG7-AP20\x00\x00', + b'78109-TG7-AS20\x00\x00', + b'78109-TG7-AT20\x00\x00', + b'78109-TG7-AU20\x00\x00', + b'78109-TG7-AX20\x00\x00', + b'78109-TG7-D020\x00\x00', + b'78109-TG7-DJ10\x00\x00', + b'78109-TG7-YK20\x00\x00', + b'78109-TG8-A420\x00\x00', + b'78109-TG8-A520\x00\x00', + b'78109-TG8-AJ10\x00\x00', + b'78109-TG8-AJ20\x00\x00', + b'78109-TG8-AK20\x00\x00', + b'78109-TG8-AS20\x00\x00', + b'78109-TGS-AB10\x00\x00', + b'78109-TGS-AC10\x00\x00', + b'78109-TGS-AD10\x00\x00', + b'78109-TGS-AJ20\x00\x00', + b'78109-TGS-AK20\x00\x00', + b'78109-TGS-AP20\x00\x00', + b'78109-TGS-AT20\x00\x00', + b'78109-TGS-AX20\x00\x00', + b'78109-TGT-AJ20\x00\x00', + b'78109-TGT-AK30\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TG7-A130\x00\x00', + b'57114-TG7-A140\x00\x00', + b'57114-TG7-A230\x00\x00', + b'57114-TG7-A240\x00\x00', + b'57114-TG7-A630\x00\x00', + b'57114-TG7-A730\x00\x00', + b'57114-TG8-A140\x00\x00', + b'57114-TG8-A240\x00\x00', + b'57114-TG8-A630\x00\x00', + b'57114-TG8-A730\x00\x00', + b'57114-TGS-A530\x00\x00', + b'57114-TGT-A530\x00\x00', + ], + }, + CAR.ACURA_RDX: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TX4-A220\x00\x00', + b'57114-TX5-A220\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TX4-A030\x00\x00', + b'36161-TX5-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX4-B010\x00\x00', + b'77959-TX4-C010\x00\x00', + b'77959-TX4-C020\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TX4-A210\x00\x00', + b'78109-TX4-A310\x00\x00', + b'78109-TX5-A210\x00\x00', + b'78109-TX5-A310\x00\x00', + ], + }, + CAR.ACURA_RDX_3G: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-5YF-A130\x00\x00', + b'37805-5YF-A230\x00\x00', + b'37805-5YF-A320\x00\x00', + b'37805-5YF-A330\x00\x00', + b'37805-5YF-A420\x00\x00', + b'37805-5YF-A430\x00\x00', + b'37805-5YF-A750\x00\x00', + b'37805-5YF-A760\x00\x00', + b'37805-5YF-A850\x00\x00', + b'37805-5YF-A870\x00\x00', + b'37805-5YF-AD20\x00\x00', + b'37805-5YF-C210\x00\x00', + b'37805-5YF-C220\x00\x00', + b'37805-5YF-C410\x00\x00', + b'37805-5YF-C420\x00\x00', + b'37805-5YF-C430\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TJB-A030\x00\x00', + b'57114-TJB-A040\x00\x00', + b'57114-TJB-A120\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TJB-A040\x00\x00', + b'36802-TJB-A050\x00\x00', + b'36802-TJB-A540\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TJB-A040\x00\x00', + b'36161-TJB-A530\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TJB-A520\x00\x00', + b'54008-TJB-A530\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28102-5YK-A610\x00\x00', + b'28102-5YK-A620\x00\x00', + b'28102-5YK-A630\x00\x00', + b'28102-5YK-A700\x00\x00', + b'28102-5YK-A711\x00\x00', + b'28102-5YK-A800\x00\x00', + b'28102-5YL-A620\x00\x00', + b'28102-5YL-A700\x00\x00', + b'28102-5YL-A711\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TJB-A140\x00\x00', + b'78109-TJB-A240\x00\x00', + b'78109-TJB-A420\x00\x00', + b'78109-TJB-AB10\x00\x00', + b'78109-TJB-AD10\x00\x00', + b'78109-TJB-AF10\x00\x00', + b'78109-TJB-AQ20\x00\x00', + b'78109-TJB-AR10\x00\x00', + b'78109-TJB-AS10\x00\x00', + b'78109-TJB-AU10\x00\x00', + b'78109-TJB-AW10\x00\x00', + b'78109-TJC-A240\x00\x00', + b'78109-TJC-A420\x00\x00', + b'78109-TJC-AA10\x00\x00', + b'78109-TJC-AD10\x00\x00', + b'78109-TJC-AF10\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TJB-A040\x00\x00', + b'77959-TJB-A120\x00\x00', + b'77959-TJB-A210\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TJB-A040\x00\x00', + b'46114-TJB-A050\x00\x00', + b'46114-TJB-A060\x00\x00', + b'46114-TJB-A120\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TJB-A040\x00\x00', + b'38897-TJB-A110\x00\x00', + b'38897-TJB-A120\x00\x00', + b'38897-TJB-A220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TJB-A030\x00\x00', + b'39990-TJB-A040\x00\x00', + b'39990-TJB-A070\x00\x00', + b'39990-TJB-A130\x00\x00', + ], + }, + CAR.RIDGELINE: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6Z-A020\x00\x00', + b'39990-T6Z-A030\x00\x00', + b'39990-T6Z-A050\x00\x00', + b'39990-T6Z-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6Z-A020\x00\x00', + b'36161-T6Z-A310\x00\x00', + b'36161-T6Z-A420\x00\x00', + b'36161-T6Z-A520\x00\x00', + b'36161-T6Z-A620\x00\x00', + b'36161-T6Z-A720\x00\x00', + b'36161-TJZ-A120\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6Z-A010\x00\x00', + b'38897-T6Z-A110\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78108-T6Z-AF10\x00\x00', + b'78109-T6Z-A420\x00\x00', + b'78109-T6Z-A510\x00\x00', + b'78109-T6Z-A710\x00\x00', + b'78109-T6Z-A810\x00\x00', + b'78109-T6Z-A910\x00\x00', + b'78109-T6Z-AA10\x00\x00', + b'78109-T6Z-C620\x00\x00', + b'78109-T6Z-C910\x00\x00', + b'78109-TJZ-A510\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6Z-A020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T6Z-A120\x00\x00', + b'57114-T6Z-A130\x00\x00', + b'57114-T6Z-A520\x00\x00', + b'57114-T6Z-A610\x00\x00', + b'57114-TJZ-A520\x00\x00', + ], + }, + CAR.INSIGHT: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TXM-A040\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TXM-A070\x00\x00', + b'36802-TXM-A080\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TXM-A050\x00\x00', + b'36161-TXM-A060\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TXM-A230\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TXM-A030\x00\x00', + b'57114-TXM-A040\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TXM-A020\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TXM-A010\x00\x00', + b'78109-TXM-A020\x00\x00', + b'78109-TXM-A030\x00\x00', + b'78109-TXM-A110\x00\x00', + b'78109-TXM-C010\x00\x00', + ], + }, + CAR.HRV: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T7A-A010\x00\x00', + b'38897-T7A-A110\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-THX-A020\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T7A-A040\x00\x00', + b'36161-T7A-A140\x00\x00', + b'36161-T7A-A240\x00\x00', + b'36161-T7A-C440\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T7A-A230\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-THW-A110\x00\x00', + b'78109-THX-A110\x00\x00', + b'78109-THX-A120\x00\x00', + b'78109-THX-A210\x00\x00', + b'78109-THX-A220\x00\x00', + b'78109-THX-C220\x00\x00', + ], + }, + CAR.HRV_3G: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-3W0-A030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-3W1-A010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-3V0-A820\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78108-3V1-A220\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-3W0-A040\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-6EH-A010\x00\x00', + ], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-6CT-A710\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-3W0-A020\x00\x00', + ], + }, + CAR.ACURA_ILX: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TX6-A010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TV9-A140\x00\x00', + b'36161-TX6-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX6-A230\x00\x00', + b'77959-TX6-C210\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T3R-A120\x00\x00', + b'78109-T3R-A410\x00\x00', + b'78109-TV9-A510\x00\x00', + ], + }, + CAR.HONDA_E: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TYF-N030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TYF-E140\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TYF-E010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TYF-G430\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78108-TYF-G610\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TYF-E030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TYF-E020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TYF-E030\x00\x00', + ], + }, + CAR.CIVIC_2022: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T24-T120\x00\x00', + b'39990-T39-A130\x00\x00', + b'39990-T43-J020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T20-A020\x00\x00', + b'38897-T20-A210\x00\x00', + b'38897-T20-A310\x00\x00', + b'38897-T20-A510\x00\x00', + b'38897-T21-A010\x00\x00', + b'38897-T24-Z120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T20-A970\x00\x00', + b'77959-T20-A980\x00\x00', + b'77959-T20-M820\x00\x00', + b'77959-T47-A940\x00\x00', + b'77959-T47-A950\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78108-T21-A220\x00\x00', + b'78108-T21-A230\x00\x00', + b'78108-T21-A620\x00\x00', + b'78108-T21-A740\x00\x00', + b'78108-T21-MB10\x00\x00', + b'78108-T22-A020\x00\x00', + b'78108-T23-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T20-A060\x00\x00', + b'36161-T20-A070\x00\x00', + b'36161-T20-A080\x00\x00', + b'36161-T24-T070\x00\x00', + b'36161-T47-A070\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T20-AB40\x00\x00', + b'57114-T24-TB30\x00\x00', + b'57114-T43-JB30\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-65D-A020\x00\x00', + b'28101-65D-A120\x00\x00', + b'28101-65H-A020\x00\x00', + b'28101-65H-A120\x00\x00', + b'28101-65J-N010\x00\x00', + ], + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-64A-A540\x00\x00', + b'37805-64A-A620\x00\x00', + b'37805-64D-P510\x00\x00', + b'37805-64L-A540\x00\x00', + b'37805-64S-A540\x00\x00', + b'37805-64S-A720\x00\x00', + b'37805-64S-AA10\x00\x00', + ], + }, +} diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index d1a287a76a..153fa1e635 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -3,8 +3,9 @@ from cereal import car from panda import Panda from openpilot.common.conversions import Conversions as CV from openpilot.common.numpy_fast import interp +from openpilot.selfdrive.car.honda.hondacan import get_pt_bus from openpilot.selfdrive.car.honda.values import CarControllerParams, CruiseButtons, HondaFlags, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, \ - HONDA_BOSCH_ALT_BRAKE_SIGNAL, HONDA_BOSCH_RADARLESS + HONDA_BOSCH_RADARLESS from openpilot.selfdrive.car import create_button_events, get_safety_config from openpilot.selfdrive.car.interfaces import CarInterfaceBase from openpilot.selfdrive.car.disable_ecu import disable_ecu @@ -275,7 +276,8 @@ class CarInterface(CarInterfaceBase): raise ValueError(f"unsupported car {candidate}") # These cars use alternate user brake msg (0x1BE) - if candidate in HONDA_BOSCH_ALT_BRAKE_SIGNAL: + if 0x1BE in fingerprint[get_pt_bus(candidate)] and candidate in HONDA_BOSCH: + ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) @@ -285,6 +287,9 @@ class CarInterface(CarInterfaceBase): if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG + if ret.enableGasInterceptor and candidate not in HONDA_BOSCH: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_GAS_INTERCEPTOR + if candidate in HONDA_BOSCH_RADARLESS: ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 38ba0f22fe..517d2550a4 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -49,6 +49,7 @@ class CarControllerParams: class HondaFlags(IntFlag): # Bosch models with alternate set of LKAS_HUD messages BOSCH_EXT_HUD = 1 + BOSCH_ALT_BRAKE = 2 # Car button codes @@ -136,7 +137,7 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS), CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS), CAR.CRV_EU: None, # HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring - CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", min_steer_speed=12. * CV.MPH_TO_MS), + CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-20", min_steer_speed=12. * CV.MPH_TO_MS), CAR.FIT: HondaCarInfo("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS), CAR.FREED: HondaCarInfo("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS), CAR.HRV: HondaCarInfo("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS), @@ -149,7 +150,7 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { HondaCarInfo("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), HondaCarInfo("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), ], - CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-23", min_steer_speed=12. * CV.MPH_TO_MS), + CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-24", min_steer_speed=12. * CV.MPH_TO_MS), CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS), } @@ -169,6 +170,13 @@ FW_QUERY_CONFIG = FwQueryConfig( ), # Data collection requests: + # Attempt to get the radarless Civic 2022+ camera FW + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + bus=0, + logging=True + ), # Log extra identifiers for current ECUs Request( [HONDA_VERSION_REQUEST], @@ -188,1378 +196,25 @@ FW_QUERY_CONFIG = FwQueryConfig( [StdQueries.UDS_VERSION_REQUEST], [StdQueries.UDS_VERSION_RESPONSE], bus=1, - logging=True, obd_multiplexing=False, ), ], + # We lose these ECUs without the comma power on these cars. + # Note that we still attempt to match with them when they are present + non_essential_ecus={ + Ecu.programmedFuelInjection: [CAR.CIVIC_BOSCH, CAR.CRV_5G], + Ecu.transmission: [CAR.CIVIC_BOSCH, CAR.CRV_5G], + Ecu.vsa: [CAR.CIVIC_BOSCH, CAR.CRV_5G], + Ecu.combinationMeter: [CAR.CIVIC_BOSCH, CAR.CRV_5G], + Ecu.gateway: [CAR.CIVIC_BOSCH, CAR.CRV_5G], + Ecu.electricBrakeBooster: [CAR.CIVIC_BOSCH, CAR.CRV_5G], + }, extra_ecus=[ # The only other ECU on PT bus accessible by camera on radarless Civic (Ecu.unknown, 0x18DAB3F1, None), ], ) -FW_VERSIONS = { - CAR.ACCORD: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-6A0-8720\x00\x00', - b'37805-6A0-9520\x00\x00', - b'37805-6A0-9620\x00\x00', - b'37805-6A0-9720\x00\x00', - b'37805-6A0-A540\x00\x00', - b'37805-6A0-A550\x00\x00', - b'37805-6A0-A640\x00\x00', - b'37805-6A0-A650\x00\x00', - b'37805-6A0-A740\x00\x00', - b'37805-6A0-A750\x00\x00', - b'37805-6A0-A840\x00\x00', - b'37805-6A0-A850\x00\x00', - b'37805-6A0-A930\x00\x00', - b'37805-6A0-AF30\x00\x00', - b'37805-6A0-AG30\x00\x00', - b'37805-6B2-C520\x00\x00', - b'37805-6A0-C540\x00\x00', - b'37805-6A1-H650\x00\x00', - b'37805-6B2-A550\x00\x00', - b'37805-6B2-A560\x00\x00', - b'37805-6B2-A650\x00\x00', - b'37805-6B2-A660\x00\x00', - b'37805-6B2-A720\x00\x00', - b'37805-6B2-A810\x00\x00', - b'37805-6B2-A820\x00\x00', - b'37805-6B2-A920\x00\x00', - b'37805-6B2-M520\x00\x00', - b'37805-6B2-Y810\x00\x00', - b'37805-6M4-B730\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TVC-A910\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6A7-A220\x00\x00', - b'28101-6A7-A230\x00\x00', - b'28101-6A7-A320\x00\x00', - b'28101-6A7-A330\x00\x00', - b'28101-6A7-A410\x00\x00', - b'28101-6A7-A510\x00\x00', - b'28101-6A7-A610\x00\x00', - b'28101-6A7-A710\x00\x00', - b'28101-6A9-H140\x00\x00', - b'28101-6A9-H420\x00\x00', - b'28102-6B8-A560\x00\x00', - b'28102-6B8-A570\x00\x00', - b'28102-6B8-A700\x00\x00', - b'28102-6B8-A800\x00\x00', - b'28102-6B8-C560\x00\x00', - b'28102-6B8-C570\x00\x00', - b'28102-6B8-M520\x00\x00', - b'28102-6B8-R700\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TVA-A060\x00\x00', - b'46114-TVA-A080\x00\x00', - b'46114-TVA-A120\x00\x00', - b'46114-TVA-A320\x00\x00', - b'46114-TVA-A050\x00\x00', - b'46114-TVE-H550\x00\x00', - b'46114-TVE-H560\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TVA-B040\x00\x00', - b'57114-TVA-B050\x00\x00', - b'57114-TVA-B060\x00\x00', - b'57114-TVA-B530\x00\x00', - b'57114-TVA-C040\x00\x00', - b'57114-TVA-C050\x00\x00', - b'57114-TVA-C060\x00\x00', - b'57114-TVA-C530\x00\x00', - b'57114-TVA-E520\x00\x00', - b'57114-TVE-H250\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBX-H120\x00\x00', - b'39990-TVA-A140\x00\x00', - b'39990-TVA-A150\x00\x00', - b'39990-TVA-A160\x00\x00', - b'39990-TVA-A340\x00\x00', - b'39990-TVA-X030\x00\x00', - b'39990-TVA-X040\x00\x00', - b'39990-TVA,A150\x00\x00', # modified firmware - b'39990-TVE-H130\x00\x00', - ], - (Ecu.unknown, 0x18da3af1, None): [ - b'39390-TVA-A020\x00\x00', - b'39390-TVA-A120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBX-H230\x00\x00', - b'77959-TVA-A460\x00\x00', - b'77959-TVA-F330\x00\x00', - b'77959-TVA-H230\x00\x00', - b'77959-TVA-L420\x00\x00', - b'77959-TVA-X330\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TBX-H310\x00\x00', - b'78109-TVA-A010\x00\x00', - b'78109-TVA-A020\x00\x00', - b'78109-TVA-A030\x00\x00', - b'78109-TVA-A110\x00\x00', - b'78109-TVA-A120\x00\x00', - b'78109-TVA-A130\x00\x00', - b'78109-TVA-A210\x00\x00', - b'78109-TVA-A220\x00\x00', - b'78109-TVA-A230\x00\x00', - b'78109-TVA-A310\x00\x00', - b'78109-TVA-C010\x00\x00', - b'78109-TVA-L010\x00\x00', - b'78109-TVA-L210\x00\x00', - b'78109-TVA-R310\x00\x00', - b'78109-TVC-A010\x00\x00', - b'78109-TVC-A020\x00\x00', - b'78109-TVC-A030\x00\x00', - b'78109-TVC-A110\x00\x00', - b'78109-TVC-A130\x00\x00', - b'78109-TVC-A210\x00\x00', - b'78109-TVC-A220\x00\x00', - b'78109-TVC-A230\x00\x00', - b'78109-TVC-C010\x00\x00', - b'78109-TVC-C110\x00\x00', - b'78109-TVC-L010\x00\x00', - b'78109-TVC-L210\x00\x00', - b'78109-TVC-M510\x00\x00', - b'78109-TVC-YF10\x00\x00', - b'78109-TVE-H610\x00\x00', - b'78109-TWA-A210\x00\x00', - ], - (Ecu.hud, 0x18da61f1, None): [ - b'78209-TVA-A010\x00\x00', - b'78209-TVA-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBX-H140\x00\x00', - b'36802-TVA-A150\x00\x00', - b'36802-TVA-A160\x00\x00', - b'36802-TVA-A170\x00\x00', - b'36802-TVA-A330\x00\x00', - b'36802-TVC-A330\x00\x00', - b'36802-TVE-H070\x00\x00', - b'36802-TWA-A070\x00\x00', - b'36802-TWA-A080\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBX-H130\x00\x00', - b'36161-TVA-A060\x00\x00', - b'36161-TVA-A330\x00\x00', - b'36161-TVC-A330\x00\x00', - b'36161-TVE-H050\x00\x00', - b'36161-TWA-A070\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TVA-A010\x00\x00', - b'38897-TVA-A020\x00\x00', - b'38897-TVA-A230\x00\x00', - b'38897-TVA-A240\x00\x00', - ], - }, - CAR.ACCORDH: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TWA-A120\x00\x00', - b'38897-TWD-J020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TWA-A040\x00\x00', - b'57114-TWA-A050\x00\x00', - b'57114-TWA-A530\x00\x00', - b'57114-TWA-B520\x00\x00', - b'57114-TWB-H030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TWA-A440\x00\x00', - b'77959-TWA-L420\x00\x00', - b'77959-TWB-H220\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TWA-A010\x00\x00', - b'78109-TWA-A020\x00\x00', - b'78109-TWA-A030\x00\x00', - b'78109-TWA-A110\x00\x00', - b'78109-TWA-A120\x00\x00', - b'78109-TWA-A130\x00\x00', - b'78109-TWA-A210\x00\x00', - b'78109-TWA-A220\x00\x00', - b'78109-TWA-A230\x00\x00', - b'78109-TWA-L010\x00\x00', - b'78109-TWA-L210\x00\x00', - b'78109-TWA-H210\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TWA-A910\x00\x00', - ], - (Ecu.hud, 0x18da61f1, None): [ - b'78209-TVA-A010\x00\x00', - b'78209-TVA-A110\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TWA-A070\x00\x00', - b'36161-TWA-A330\x00\x00', - b'36161-TWB-H040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TWA-A070\x00\x00', - b'36802-TWA-A080\x00\x00', - b'36802-TWA-A330\x00\x00', - b'36802-TWB-H060\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TVA-A160\x00\x00', - b'39990-TVA-A150\x00\x00', - b'39990-TVA-A340\x00\x00', - b'39990-TWB-H120\x00\x00', - ], - }, - CAR.CIVIC: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-5AA-A640\x00\x00', - b'37805-5AA-A650\x00\x00', - b'37805-5AA-A670\x00\x00', - b'37805-5AA-A680\x00\x00', - b'37805-5AA-A810\x00\x00', - b'37805-5AA-C640\x00\x00', - b'37805-5AA-C680\x00\x00', - b'37805-5AA-C820\x00\x00', - b'37805-5AA-L650\x00\x00', - b'37805-5AA-L660\x00\x00', - b'37805-5AA-L680\x00\x00', - b'37805-5AA-L690\x00\x00', - b'37805-5AA-L810\000\000', - b'37805-5AG-Q710\x00\x00', - b'37805-5AJ-A610\x00\x00', - b'37805-5AJ-A620\x00\x00', - b'37805-5AJ-L610\x00\x00', - b'37805-5BA-A310\x00\x00', - b'37805-5BA-A510\x00\x00', - b'37805-5BA-A740\x00\x00', - b'37805-5BA-A760\x00\x00', - b'37805-5BA-A930\x00\x00', - b'37805-5BA-A960\x00\x00', - b'37805-5BA-C860\x00\x00', - b'37805-5BA-L410\x00\x00', - b'37805-5BA-L760\x00\x00', - b'37805-5BA-L930\x00\x00', - b'37805-5BA-L940\x00\x00', - b'37805-5BA-L960\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A040\x00\x00', - b'28101-5CG-A050\x00\x00', - b'28101-5CG-A070\x00\x00', - b'28101-5CG-A080\x00\x00', - b'28101-5CG-A320\x00\x00', - b'28101-5CG-A810\x00\x00', - b'28101-5CG-A820\x00\x00', - b'28101-5DJ-A040\x00\x00', - b'28101-5DJ-A060\x00\x00', - b'28101-5DJ-A510\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBA-A540\x00\x00', - b'57114-TBA-A550\x00\x00', - b'57114-TBA-A560\x00\x00', - b'57114-TBA-A570\x00\x00', - b'57114-TEA-Q220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA,A030\x00\x00', # modified firmware - b'39990-TBA-A030\x00\x00', - b'39990-TBG-A030\x00\x00', - b'39990-TEA-T020\x00\x00', - b'39990-TEG-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A030\x00\x00', - b'77959-TBA-A040\x00\x00', - b'77959-TBG-A030\x00\x00', - b'77959-TEA-Q820\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TBA-A510\x00\x00', - b'78109-TBA-A520\x00\x00', - b'78109-TBA-A530\x00\x00', - b'78109-TBA-C520\x00\x00', - b'78109-TBC-A310\x00\x00', - b'78109-TBC-A320\x00\x00', - b'78109-TBC-A510\x00\x00', - b'78109-TBC-A520\x00\x00', - b'78109-TBC-A530\x00\x00', - b'78109-TBC-C510\x00\x00', - b'78109-TBC-C520\x00\x00', - b'78109-TBC-C530\x00\x00', - b'78109-TBH-A510\x00\x00', - b'78109-TBH-A530\x00\x00', - b'78109-TED-Q510\x00\x00', - b'78109-TEG-A310\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TBA-A020\x00\x00', - b'36161-TBA-A030\x00\x00', - b'36161-TBA-A040\x00\x00', - b'36161-TBC-A020\x00\x00', - b'36161-TBC-A030\x00\x00', - b'36161-TED-Q320\x00\x00', - b'36161-TEG-A010\x00\x00', - b'36161-TEG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A010\x00\x00', - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.CIVIC_BOSCH: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-5AA-A940\x00\x00', - b'37805-5AA-A950\x00\x00', - b'37805-5AA-C950\x00\x00', - b'37805-5AA-L940\x00\x00', - b'37805-5AA-L950\x00\x00', - b'37805-5AG-Z910\x00\x00', - b'37805-5AJ-A750\x00\x00', - b'37805-5AJ-L750\x00\x00', - b'37805-5AK-T530\x00\x00', - b'37805-5AN-A750\x00\x00', - b'37805-5AN-A830\x00\x00', - b'37805-5AN-A840\x00\x00', - b'37805-5AN-A930\x00\x00', - b'37805-5AN-A940\x00\x00', - b'37805-5AN-A950\x00\x00', - b'37805-5AN-AG20\x00\x00', - b'37805-5AN-AH20\x00\x00', - b'37805-5AN-AJ30\x00\x00', - b'37805-5AN-AK10\x00\x00', - b'37805-5AN-AK20\x00\x00', - b'37805-5AN-AR10\x00\x00', - b'37805-5AN-AR20\x00\x00', - b'37805-5AN-CH20\x00\x00', - b'37805-5AN-E630\x00\x00', - b'37805-5AN-E720\x00\x00', - b'37805-5AN-E820\x00\x00', - b'37805-5AN-J820\x00\x00', - b'37805-5AN-L840\x00\x00', - b'37805-5AN-L930\x00\x00', - b'37805-5AN-L940\x00\x00', - b'37805-5AN-LF20\x00\x00', - b'37805-5AN-LH20\x00\x00', - b'37805-5AN-LJ20\x00\x00', - b'37805-5AN-LR20\x00\x00', - b'37805-5AN-LS20\x00\x00', - b'37805-5AW-G720\x00\x00', - b'37805-5AZ-E850\x00\x00', - b'37805-5AZ-G540\x00\x00', - b'37805-5AZ-G740\x00\x00', - b'37805-5AZ-G840\x00\x00', - b'37805-5BB-A530\x00\x00', - b'37805-5BB-A540\x00\x00', - b'37805-5BB-A630\x00\x00', - b'37805-5BB-A640\x00\x00', - b'37805-5BB-C540\x00\x00', - b'37805-5BB-C630\x00\x00', - b'37805-5BB-C640\x00\x00', - b'37805-5BB-L540\x00\x00', - b'37805-5BB-L630\x00\x00', - b'37805-5BB-L640\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A920\x00\x00', - b'28101-5CG-AB10\x00\x00', - b'28101-5CG-C110\x00\x00', - b'28101-5CG-C220\x00\x00', - b'28101-5CG-C320\x00\x00', - b'28101-5CG-G020\x00\x00', - b'28101-5CG-L020\x00\x00', - b'28101-5CK-A130\x00\x00', - b'28101-5CK-A140\x00\x00', - b'28101-5CK-A150\x00\x00', - b'28101-5CK-C130\x00\x00', - b'28101-5CK-C140\x00\x00', - b'28101-5CK-C150\x00\x00', - b'28101-5CK-G210\x00\x00', - b'28101-5CK-J710\x00\x00', - b'28101-5CK-Q610\x00\x00', - b'28101-5DJ-A610\x00\x00', - b'28101-5DJ-A710\x00\x00', - b'28101-5DV-E330\x00\x00', - b'28101-5DV-E610\x00\x00', - b'28101-5DV-E820\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBG-A330\x00\x00', - b'57114-TBG-A340\x00\x00', - b'57114-TBG-A350\x00\x00', - b'57114-TGG-A340\x00\x00', - b'57114-TGG-C320\x00\x00', - b'57114-TGG-G320\x00\x00', - b'57114-TGG-L320\x00\x00', - b'57114-TGG-L330\x00\x00', - b'57114-TGK-T320\x00\x00', - b'57114-TGL-G330\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA-C020\x00\x00', - b'39990-TBA-C120\x00\x00', - b'39990-TEA-T820\x00\x00', - b'39990-TEZ-T020\x00\x00', - b'39990-TGG-A020\x00\x00', - b'39990-TGG-A120\x00\x00', - b'39990-TGG-J510\x00\x00', - b'39990-TGL-E130\x00\x00', - b'39990-TGN-E120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A060\x00\x00', - b'77959-TBG-A050\x00\x00', - b'77959-TEA-G020\x00\x00', - b'77959-TGG-A020\x00\x00', - b'77959-TGG-A030\x00\x00', - b'77959-TGG-E010\x00\x00', - b'77959-TGG-G010\x00\x00', - b'77959-TGG-G110\x00\x00', - b'77959-TGG-J320\x00\x00', - b'77959-TGG-Z820\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TBA-A110\x00\x00', - b'78109-TBA-A910\x00\x00', - b'78109-TBA-C340\x00\x00', - b'78109-TBA-C910\x00\x00', - b'78109-TBC-A740\x00\x00', - b'78109-TBC-C540\x00\x00', - b'78109-TBG-A110\x00\x00', - b'78109-TBH-A710\x00\x00', - b'78109-TEG-A720\x00\x00', - b'78109-TFJ-G020\x00\x00', - b'78109-TGG-9020\x00\x00', - b'78109-TGG-A210\x00\x00', - b'78109-TGG-A220\x00\x00', - b'78109-TGG-A310\x00\x00', - b'78109-TGG-A320\x00\x00', - b'78109-TGG-A330\x00\x00', - b'78109-TGG-A610\x00\x00', - b'78109-TGG-A620\x00\x00', - b'78109-TGG-A810\x00\x00', - b'78109-TGG-A820\x00\x00', - b'78109-TGG-C220\x00\x00', - b'78109-TGG-E110\x00\x00', - b'78109-TGG-G030\x00\x00', - b'78109-TGG-G230\x00\x00', - b'78109-TGG-G410\x00\x00', - b'78109-TGK-Z410\x00\x00', - b'78109-TGL-G120\x00\x00', - b'78109-TGL-G130\x00\x00', - b'78109-TGL-G210\x00\x00', - b'78109-TGL-G230\x00\x00', - b'78109-TGL-GM10\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBA-A150\x00\x00', - b'36802-TBA-A160\x00\x00', - b'36802-TFJ-G060\x00\x00', - b'36802-TGG-A050\x00\x00', - b'36802-TGG-A060\x00\x00', - b'36802-TGG-A130\x00\x00', - b'36802-TGG-G040\x00\x00', - b'36802-TGG-G130\x00\x00', - b'36802-TGK-Q120\x00\x00', - b'36802-TGL-G040\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBA-A130\x00\x00', - b'36161-TBA-A140\x00\x00', - b'36161-TFJ-G070\x00\x00', - b'36161-TGG-A060\x00\x00', - b'36161-TGG-A080\x00\x00', - b'36161-TGG-A120\x00\x00', - b'36161-TGG-G050\x00\x00', - b'36161-TGG-G130\x00\x00', - b'36161-TGG-G140\x00\x00', - b'36161-TGK-Q120\x00\x00', - b'36161-TGL-G050\x00\x00', - b'36161-TGL-G070\x00\x00', - b'36161-TGG-G070\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A110\x00\x00', - b'38897-TBA-A020\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'39494-TGL-G030\x00\x00', - ], - }, - CAR.CIVIC_BOSCH_DIESEL: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-59N-G630\x00\x00', - b'37805-59N-G830\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-59Y-G220\x00\x00', - b'28101-59Y-G620\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TGN-E320\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TFK-G020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TFK-G210\x00\x00', - b'77959-TGN-G220\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TFK-G020\x00\x00', - b'78109-TGN-G120\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TFK-G130\x00\x00', - b'36802-TGN-G130\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TGN-E010\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TFK-G130\x00\x00', - b'36161-TGN-G130\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.CRV: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1W-A230\x00\x00', - b'57114-T1W-A240\x00\x00', - b'57114-TFF-A940\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T0A-A230\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-T1W-A210\x00\x00', - b'78109-T1W-C210\x00\x00', - b'78109-T1X-A210\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1W-A830\x00\x00', - b'36161-T1W-C830\x00\x00', - b'36161-T1X-A830\x00\x00', - ], - }, - CAR.CRV_5G: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-5PA-AH20\x00\x00', - b'37805-5PA-3060\x00\x00', - b'37805-5PA-3080\x00\x00', - b'37805-5PA-3180\x00\x00', - b'37805-5PA-4050\x00\x00', - b'37805-5PA-4150\x00\x00', - b'37805-5PA-6520\x00\x00', - b'37805-5PA-6530\x00\x00', - b'37805-5PA-6630\x00\x00', - b'37805-5PA-6640\x00\x00', - b'37805-5PA-7630\x00\x00', - b'37805-5PA-9630\x00\x00', - b'37805-5PA-9640\x00\x00', - b'37805-5PA-9730\x00\x00', - b'37805-5PA-9830\x00\x00', - b'37805-5PA-9840\x00\x00', - b'37805-5PA-A650\x00\x00', - b'37805-5PA-A670\x00\x00', - b'37805-5PA-A680\x00\x00', - b'37805-5PA-A850\x00\x00', - b'37805-5PA-A870\x00\x00', - b'37805-5PA-A880\x00\x00', - b'37805-5PA-A890\x00\x00', - b'37805-5PA-AB10\x00\x00', - b'37805-5PA-AD10\x00\x00', - b'37805-5PA-AF20\x00\x00', - b'37805-5PA-C680\x00\x00', - b'37805-5PD-Q630\x00\x00', - b'37805-5PF-F730\x00\x00', - b'37805-5PF-M630\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5RG-A020\x00\x00', - b'28101-5RG-A030\x00\x00', - b'28101-5RG-A040\x00\x00', - b'28101-5RG-A120\x00\x00', - b'28101-5RG-A220\x00\x00', - b'28101-5RH-A020\x00\x00', - b'28101-5RH-A030\x00\x00', - b'28101-5RH-A040\x00\x00', - b'28101-5RH-A120\x00\x00', - b'28101-5RH-A220\x00\x00', - b'28101-5RL-Q010\x00\x00', - b'28101-5RM-F010\x00\x00', - b'28101-5RM-K010\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TLA-A040\x00\x00', - b'57114-TLA-A050\x00\x00', - b'57114-TLA-A060\x00\x00', - b'57114-TLB-A830\x00\x00', - b'57114-TMC-Z040\x00\x00', - b'57114-TMC-Z050\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TLA-A040\x00\x00', - b'39990-TLA-A110\x00\x00', - b'39990-TLA-A220\x00\x00', - b'39990-TLA,A040\x00\x00', # modified firmware - b'39990-TME-T030\x00\x00', - b'39990-TME-T120\x00\x00', - b'39990-TMT-T010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TLA-A040\x00\x00', - b'46114-TLA-A050\x00\x00', - b'46114-TLA-A930\x00\x00', - b'46114-TMC-U020\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TLA-A110\x00\x00', - b'78109-TLA-A120\x00\x00', - b'78109-TLA-A210\x00\x00', - b'78109-TLA-A220\x00\x00', - b'78109-TLA-C020\x00\x00', - b'78109-TLA-C110\x00\x00', - b'78109-TLA-C210\x00\x00', - b'78109-TLA-C310\x00\x00', - b'78109-TLB-A020\x00\x00', - b'78109-TLB-A110\x00\x00', - b'78109-TLB-A120\x00\x00', - b'78109-TLB-A210\x00\x00', - b'78109-TLB-A220\x00\x00', - b'78109-TMC-Q210\x00\x00', - b'78109-TMM-F210\x00\x00', - b'78109-TMM-M110\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TLA-A010\x00\x00', - b'38897-TLA-A110\x00\x00', - b'38897-TNY-G010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TLA-A040\x00\x00', - b'36802-TLA-A050\x00\x00', - b'36802-TLA-A060\x00\x00', - b'36802-TMC-Q040\x00\x00', - b'36802-TMC-Q070\x00\x00', - b'36802-TNY-A030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TLA-A060\x00\x00', - b'36161-TLA-A070\x00\x00', - b'36161-TLA-A080\x00\x00', - b'36161-TMC-Q020\x00\x00', - b'36161-TMC-Q030\x00\x00', - b'36161-TMC-Q040\x00\x00', - b'36161-TNY-A020\x00\x00', - b'36161-TNY-A030\x00\x00', - b'36161-TNY-A040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-A240\x00\x00', - b'77959-TLA-A250\x00\x00', - b'77959-TLA-A320\x00\x00', - b'77959-TLA-A410\x00\x00', - b'77959-TLA-A420\x00\x00', - b'77959-TLA-Q040\x00\x00', - b'77959-TLA-Z040\x00\x00', - b'77959-TMM-F040\x00\x00', - ], - }, - CAR.CRV_EU: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-R5Z-G740\x00\x00', - b'37805-R5Z-G780\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [b'57114-T1V-G920\x00\x00'], - (Ecu.fwdRadar, 0x18dab0f1, None): [b'36161-T1V-G520\x00\x00'], - (Ecu.shiftByWire, 0x18da0bf1, None): [b'54008-T1V-G010\x00\x00'], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5LH-E120\x00\x00', - b'28103-5LH-E100\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-T1V-G020\x00\x00', - b'78109-T1B-3050\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [b'77959-T1G-G940\x00\x00'], - }, - CAR.CRV_HYBRID: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TPA-G020\x00\x00', - b'57114-TPG-A020\x00\x00', - b'57114-TMB-H030\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TPA-G030\x00\x00', - b'39990-TPG-A020\x00\x00', - b'39990-TMA-H020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TMA-H110\x00\x00', - b'38897-TPG-A110\x00\x00', - b'38897-TPG-A210\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TMB-H510\x00\x00', - b'54008-TMB-H610\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TMB-H040\x00\x00', - b'36161-TPA-E050\x00\x00', - b'36161-TPG-A030\x00\x00', - b'36161-TPG-A040\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TMB-H220\x00\x00', - b'78109-TPA-G520\x00\x00', - b'78109-TPG-A110\x00\x00', - b'78109-TPG-A210\x00\x00', - ], - (Ecu.hud, 0x18da61f1, None): [ - b'78209-TLA-X010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TPA-E040\x00\x00', - b'36802-TPG-A020\x00\x00', - b'36802-TMB-H040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-C320\x00\x00', - b'77959-TLA-C410\x00\x00', - b'77959-TLA-C420\x00\x00', - b'77959-TLA-G220\x00\x00', - b'77959-TLA-H240\x00\x00', - ], - }, - CAR.FIT: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T5R-L020\x00\x00', - b'57114-T5R-L220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T5R-C020\x00\x00', - b'39990-T5R-C030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T5A-J010\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-T5A-A210\x00\x00', - b'78109-T5A-A410\x00\x00', - b'78109-T5A-A420\x00\x00', - b'78109-T5A-A910\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T5R-A040\x00\x00', - b'36161-T5R-A240\x00\x00', - b'36161-T5R-A520\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T5R-A230\x00\x00', - ], - }, - CAR.FREED: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TDK-J010\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TDK-J050\x00\x00', - b'39990-TDK-N020\x00\x00', - ], - # TODO: vsa is "essential" for fpv2 but doesn't appear on some models - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TDK-J120\x00\x00', - b'57114-TDK-J330\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TDK-J310\x00\x00', - b'78109-TDK-J320\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TDK-J070\x00\x00', - b'36161-TDK-J080\x00\x00', - b'36161-TDK-J530\x00\x00', - ], - }, - CAR.ODYSSEY: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-THR-A010\x00\x00', - b'38897-THR-A020\x00\x00', - ], - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-5MR-4080\x00\x00', - b'37805-5MR-A240\x00\x00', - b'37805-5MR-A250\x00\x00', - b'37805-5MR-A310\x00\x00', - b'37805-5MR-A740\x00\x00', - b'37805-5MR-A750\x00\x00', - b'37805-5MR-A840\x00\x00', - b'37805-5MR-C620\x00\x00', - b'37805-5MR-D530\x00\x00', - b'37805-5MR-K730\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THR-A020\x00\x00', - b'39990-THR-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-THR-A010\x00\x00', - b'77959-THR-A110\x00\x00', - b'77959-THR-X010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-THR-A020\x00\x00', - b'36161-THR-A030\x00\x00', - b'36161-THR-A110\x00\x00', - b'36161-THR-A720\x00\x00', - b'36161-THR-A730\x00\x00', - b'36161-THR-A810\x00\x00', - b'36161-THR-A910\x00\x00', - b'36161-THR-C010\x00\x00', - b'36161-THR-D110\x00\x00', - b'36161-THR-K020\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5NZ-A110\x00\x00', - b'28101-5NZ-A310\x00\x00', - b'28101-5NZ-C310\x00\x00', - b'28102-5MX-A001\x00\x00', - b'28102-5MX-A600\x00\x00', - b'28102-5MX-A610\x00\x00', - b'28102-5MX-A710\x00\x00', - b'28102-5MX-A900\x00\x00', - b'28102-5MX-A910\x00\x00', - b'28102-5MX-C001\x00\x00', - b'28102-5MX-D001\x00\x00', - b'28102-5MX-D710\x00\x00', - b'28102-5MX-K610\x00\x00', - b'28103-5NZ-A100\x00\x00', - b'28103-5NZ-A300\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-THR-A040\x00\x00', - b'57114-THR-A110\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-THR-A220\x00\x00', - b'78109-THR-A230\x00\x00', - b'78109-THR-A420\x00\x00', - b'78109-THR-A430\x00\x00', - b'78109-THR-A720\x00\x00', - b'78109-THR-A820\x00\x00', - b'78109-THR-A830\x00\x00', - b'78109-THR-AB20\x00\x00', - b'78109-THR-AB30\x00\x00', - b'78109-THR-AB40\x00\x00', - b'78109-THR-AC20\x00\x00', - b'78109-THR-AC30\x00\x00', - b'78109-THR-AC40\x00\x00', - b'78109-THR-AC50\x00\x00', - b'78109-THR-AD30\x00\x00', - b'78109-THR-AE20\x00\x00', - b'78109-THR-AE30\x00\x00', - b'78109-THR-AE40\x00\x00', - b'78109-THR-AK10\x00\x00', - b'78109-THR-AL10\x00\x00', - b'78109-THR-AN10\x00\x00', - b'78109-THR-C220\x00\x00', - b'78109-THR-C330\x00\x00', - b'78109-THR-CE20\x00\x00', - b'78109-THR-DA20\x00\x00', - b'78109-THR-DA30\x00\x00', - b'78109-THR-DA40\x00\x00', - b'78109-THR-K120\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-THR-A020\x00\x00', - ], - }, - CAR.ODYSSEY_CHN: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6D-H220\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6A-J010\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-T6A-F310\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6A-P040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6A-P110\x00\x00', - ], - }, - CAR.PILOT: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TG7-A520\x00\x00', - b'54008-TG7-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5EY-A050\x00\x00', - b'28101-5EY-A100\x00\x00', - b'28101-5EZ-A050\x00\x00', - b'28101-5EZ-A060\x00\x00', - b'28101-5EZ-A100\x00\x00', - b'28101-5EZ-A210\x00\x00', - b'28101-5EZ-A600\x00\x00', - b'28101-5EZ-A430\x00\x00', - b'28101-5EZ-A700\x00\x00', - ], - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-RLV-4060\x00\x00', - b'37805-RLV-4070\x00\x00', - b'37805-RLV-A830\x00\x00', - b'37805-RLV-A840\x00\x00', - b'37805-RLV-C430\x00\x00', - b'37805-RLV-C510\x00\x00', - b'37805-RLV-C520\x00\x00', - b'37805-RLV-C530\x00\x00', - b'37805-RLV-C910\x00\x00', - b'37805-RLV-B220\x00\x00', - b'37805-RLV-B210\x00\x00', - b'37805-RLV-L160\x00\x00', - b'37805-RLV-B420\x00\x00', - b'37805-RLV-F120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TG7-A030\x00\x00', - b'38897-TG7-A040\x00\x00', - b'38897-TG7-A110\x00\x00', - b'38897-TG7-A210\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TG7-A030\x00\x00', - b'39990-TG7-A040\x00\x00', - b'39990-TG7-A060\x00\x00', - b'39990-TG7-A070\x00\x00', - b'39990-TGS-A230\x00\x00', - b'39990-TGS-A320\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TG7-A310\x00\x00', - b'36161-TG7-A520\x00\x00', - b'36161-TG7-A630\x00\x00', - b'36161-TG7-A720\x00\x00', - b'36161-TG7-A820\x00\x00', - b'36161-TG7-A930\x00\x00', - b'36161-TG7-C520\x00\x00', - b'36161-TG7-D520\x00\x00', - b'36161-TG7-D630\x00\x00', - b'36161-TG7-Y630\x00\x00', - b'36161-TG8-A520\x00\x00', - b'36161-TG8-A630\x00\x00', - b'36161-TG8-A720\x00\x00', - b'36161-TG8-A830\x00\x00', - b'36161-TGS-A130\x00\x00', - b'36161-TGT-A030\x00\x00', - b'36161-TGT-A130\x00\x00', - b'36161-TGS-A030\x00\x00', - b'36161-TGS-A220\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TG7-A020\x00\x00', - b'77959-TG7-A110\x00\x00', - b'77959-TG7-A210\x00\x00', - b'77959-TG7-Y210\x00\x00', - b'77959-TGS-A010\x00\x00', - b'77959-TGS-A110\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TG7-A040\x00\x00', - b'78109-TG7-A050\x00\x00', - b'78109-TG7-A420\x00\x00', - b'78109-TG7-A520\x00\x00', - b'78109-TG7-A720\x00\x00', - b'78109-TG7-AJ10\x00\x00', - b'78109-TG7-AJ20\x00\x00', - b'78109-TG7-AK10\x00\x00', - b'78109-TG7-AK20\x00\x00', - b'78109-TG7-AM20\x00\x00', - b'78109-TG7-AP10\x00\x00', - b'78109-TG7-AP20\x00\x00', - b'78109-TG7-AS20\x00\x00', - b'78109-TG7-AT20\x00\x00', - b'78109-TG7-AU20\x00\x00', - b'78109-TG7-AX20\x00\x00', - b'78109-TG7-D020\x00\x00', - b'78109-TG7-DJ10\x00\x00', - b'78109-TG7-YK20\x00\x00', - b'78109-TG8-A420\x00\x00', - b'78109-TG8-A520\x00\x00', - b'78109-TG8-AJ10\x00\x00', - b'78109-TG8-AJ20\x00\x00', - b'78109-TG8-AK20\x00\x00', - b'78109-TGS-AK20\x00\x00', - b'78109-TGS-AP20\x00\x00', - b'78109-TGT-AJ20\x00\x00', - b'78109-TGT-AK30\x00\x00', - b'78109-TGS-AT20\x00\x00', - b'78109-TGS-AX20\x00\x00', - b'78109-TGS-AJ20\x00\x00', - b'78109-TGS-AC10\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TG7-A130\x00\x00', - b'57114-TG7-A140\x00\x00', - b'57114-TG7-A230\x00\x00', - b'57114-TG7-A240\x00\x00', - b'57114-TG7-A630\x00\x00', - b'57114-TG7-A730\x00\x00', - b'57114-TG8-A140\x00\x00', - b'57114-TG8-A240\x00\x00', - b'57114-TG8-A630\x00\x00', - b'57114-TG8-A730\x00\x00', - b'57114-TGS-A530\x00\x00', - b'57114-TGT-A530\x00\x00', - ], - }, - CAR.ACURA_RDX: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TX5-A220\x00\x00', - b'57114-TX4-A220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TX5-A030\x00\x00', - b'36161-TX4-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX4-C010\x00\x00', - b'77959-TX4-B010\x00\x00', - b'77959-TX4-C020\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TX5-A310\x00\x00', - b'78109-TX4-A210\x00\x00', - b'78109-TX4-A310\x00\x00', - ], - }, - CAR.ACURA_RDX_3G: { - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-5YF-A130\x00\x00', - b'37805-5YF-A230\x00\x00', - b'37805-5YF-A320\x00\x00', - b'37805-5YF-A330\x00\x00', - b'37805-5YF-A420\x00\x00', - b'37805-5YF-A430\x00\x00', - b'37805-5YF-A750\x00\x00', - b'37805-5YF-A850\x00\x00', - b'37805-5YF-A870\x00\x00', - b'37805-5YF-AD20\x00\x00', - b'37805-5YF-C210\x00\x00', - b'37805-5YF-C220\x00\x00', - b'37805-5YF-C410\000\000', - b'37805-5YF-C420\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TJB-A030\x00\x00', - b'57114-TJB-A040\x00\x00', - b'57114-TJB-A120\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TJB-A040\x00\x00', - b'36802-TJB-A050\x00\x00', - b'36802-TJB-A540\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TJB-A040\x00\x00', - b'36161-TJB-A530\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TJB-A520\x00\x00', - b'54008-TJB-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28102-5YK-A610\x00\x00', - b'28102-5YK-A620\x00\x00', - b'28102-5YK-A630\x00\x00', - b'28102-5YK-A700\x00\x00', - b'28102-5YK-A711\x00\x00', - b'28102-5YK-A800\x00\x00', - b'28102-5YL-A620\x00\x00', - b'28102-5YL-A700\x00\x00', - b'28102-5YL-A711\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TJB-A140\x00\x00', - b'78109-TJB-A240\x00\x00', - b'78109-TJB-A420\x00\x00', - b'78109-TJB-AB10\x00\x00', - b'78109-TJB-AD10\x00\x00', - b'78109-TJB-AF10\x00\x00', - b'78109-TJB-AQ20\x00\x00', - b'78109-TJB-AR10\x00\x00', - b'78109-TJB-AS10\000\000', - b'78109-TJB-AU10\x00\x00', - b'78109-TJB-AW10\x00\x00', - b'78109-TJC-A420\x00\x00', - b'78109-TJC-AA10\x00\x00', - b'78109-TJC-AD10\x00\x00', - b'78109-TJC-AF10\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TJB-A040\x00\x00', - b'77959-TJB-A120\x00\x00', - b'77959-TJB-A210\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TJB-A040\x00\x00', - b'46114-TJB-A050\x00\x00', - b'46114-TJB-A060\x00\x00', - b'46114-TJB-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TJB-A040\x00\x00', - b'38897-TJB-A110\x00\x00', - b'38897-TJB-A120\x00\x00', - b'38897-TJB-A220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TJB-A030\x00\x00', - b'39990-TJB-A040\x00\x00', - b'39990-TJB-A070\x00\x00', - b'39990-TJB-A130\x00\x00', - ], - }, - CAR.RIDGELINE: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6Z-A020\x00\x00', - b'39990-T6Z-A030\x00\x00', - b'39990-T6Z-A050\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6Z-A020\x00\x00', - b'36161-T6Z-A310\x00\x00', - b'36161-T6Z-A420\x00\x00', - b'36161-T6Z-A520\x00\x00', - b'36161-T6Z-A620\x00\x00', - b'36161-TJZ-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6Z-A010\x00\x00', - b'38897-T6Z-A110\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-T6Z-A420\x00\x00', - b'78109-T6Z-A510\x00\x00', - b'78109-T6Z-A710\x00\x00', - b'78109-T6Z-A810\x00\x00', - b'78109-T6Z-A910\x00\x00', - b'78109-T6Z-AA10\x00\x00', - b'78109-T6Z-C620\x00\x00', - b'78109-T6Z-C910\x00\x00', - b'78109-TJZ-A510\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6Z-A020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T6Z-A120\x00\x00', - b'57114-T6Z-A130\x00\x00', - b'57114-T6Z-A520\x00\x00', - b'57114-TJZ-A520\x00\x00', - ], - }, - CAR.INSIGHT: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TXM-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TXM-A070\x00\x00', - b'36802-TXM-A080\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TXM-A050\x00\x00', - b'36161-TXM-A060\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TXM-A230\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TXM-A030\x00\x00', - b'57114-TXM-A040\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TWA-A910\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TXM-A020\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-TXM-A010\x00\x00', - b'78109-TXM-A020\x00\x00', - b'78109-TXM-A110\x00\x00', - b'78109-TXM-C010\x00\x00', - b'78109-TXM-A030\x00\x00', - ], - }, - CAR.HRV: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T7A-A010\x00\x00', - b'38897-T7A-A110\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THX-A020\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T7A-A140\x00\x00', - b'36161-T7A-A240\x00\x00', - b'36161-T7A-C440\x00\x00', - b'36161-T7A-A040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T7A-A230\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-THX-A110\x00\x00', - b'78109-THX-A120\x00\x00', - b'78109-THX-A210\x00\x00', - b'78109-THX-A220\x00\x00', - b'78109-THX-C220\x00\x00', - b'78109-THW-A110\x00\x00', - ], - }, - CAR.HRV_3G: { - (Ecu.eps, 0x18DA30F1, None): [ - b'39990-3W0-A030\x00\x00', - ], - (Ecu.gateway, 0x18DAEFF1, None): [ - b'38897-3W1-A010\x00\x00', - ], - (Ecu.srs, 0x18DA53F1, None): [ - b'77959-3V0-A820\x00\x00', - ], - (Ecu.combinationMeter, 0x18DA60F1, None): [ - b'78108-3V1-A220\x00\x00', - ], - (Ecu.vsa, 0x18DA28F1, None): [ - b'57114-3W0-A040\x00\x00', - ], - (Ecu.transmission, 0x18DA1EF1, None): [ - b'28101-6EH-A010\x00\x00', - ], - (Ecu.programmedFuelInjection, 0x18DA10F1, None): [ - b'37805-6CT-A710\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18DA2BF1, None): [ - b'46114-3W0-A020\x00\x00', - ], - }, - CAR.ACURA_ILX: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TX6-A010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TV9-A140\x00\x00', - b'36161-TX6-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX6-A230\x00\x00', - b'77959-TX6-C210\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ - b'78109-T3R-A120\x00\x00', - b'78109-T3R-A410\x00\x00', - b'78109-TV9-A510\x00\x00', - ], - }, - CAR.HONDA_E:{ - (Ecu.eps, 0x18DA30F1, None):[ - b'39990-TYF-N030\x00\x00' - ], - (Ecu.gateway, 0x18DAEFF1, None):[ - b'38897-TYF-E140\x00\x00' - ], - (Ecu.shiftByWire, 0x18DA0BF1, None):[ - b'54008-TYF-E010\x00\x00' - ], - (Ecu.srs, 0x18DA53F1, None):[ - b'77959-TYF-G430\x00\x00' - ], - (Ecu.combinationMeter, 0x18DA60F1, None):[ - b'78108-TYF-G610\x00\x00' - ], - (Ecu.fwdRadar, 0x18DAB0F1, None):[ - b'36802-TYF-E030\x00\x00' - ], - (Ecu.fwdCamera, 0x18DAB5F1, None):[ - b'36161-TYF-E020\x00\x00' - ], - (Ecu.vsa, 0x18DA28F1, None):[ - b'57114-TYF-E030\x00\x00' - ], - }, - CAR.CIVIC_2022: { - (Ecu.eps, 0x18DA30F1, None): [ - b'39990-T39-A130\x00\x00', - b'39990-T43-J020\x00\x00', - b'39990-T24-T120\x00\x00', - ], - (Ecu.gateway, 0x18DAEFF1, None): [ - b'38897-T20-A020\x00\x00', - b'38897-T20-A510\x00\x00', - b'38897-T21-A010\x00\x00', - b'38897-T20-A210\x00\x00', - b'38897-T20-A310\x00\x00', - b'38897-T24-Z120\x00\x00', - ], - (Ecu.srs, 0x18DA53F1, None): [ - b'77959-T20-A970\x00\x00', - b'77959-T47-A940\x00\x00', - b'77959-T47-A950\x00\x00', - b'77959-T20-M820\x00\x00', - b'77959-T20-A980\x00\x00', - ], - (Ecu.combinationMeter, 0x18DA60F1, None): [ - b'78108-T21-A220\x00\x00', - b'78108-T21-A620\x00\x00', - b'78108-T23-A110\x00\x00', - b'78108-T21-A230\x00\x00', - b'78108-T22-A020\x00\x00', - b'78108-T21-MB10\x00\x00', - b'78108-T21-A740\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T20-A070\x00\x00', - b'36161-T20-A080\x00\x00', - b'36161-T20-A060\x00\x00', - b'36161-T47-A070\x00\x00', - b'36161-T24-T070\x00\x00', - ], - (Ecu.vsa, 0x18DA28F1, None): [ - b'57114-T20-AB40\x00\x00', - b'57114-T43-JB30\x00\x00', - b'57114-T24-TB30\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-65D-A020\x00\x00', - b'28101-65D-A120\x00\x00', - b'28101-65H-A020\x00\x00', - b'28101-65H-A120\x00\x00', - b'28101-65J-N010\x00\x00', - ], - (Ecu.programmedFuelInjection, 0x18da10f1, None): [ - b'37805-64L-A540\x00\x00', - b'37805-64S-A540\x00\x00', - b'37805-64S-A720\x00\x00', - b'37805-64A-A540\x00\x00', - b'37805-64A-A620\x00\x00', - b'37805-64D-P510\x00\x00', - b'37805-64S-AA10\x00\x00', - ], - }, -} DBC = { CAR.ACCORD: dbc_dict('honda_accord_2018_can_generated', None), @@ -1598,5 +253,4 @@ HONDA_NIDEC_ALT_SCM_MESSAGES = {CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_E CAR.PILOT, CAR.RIDGELINE} HONDA_BOSCH = {CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G} -HONDA_BOSCH_ALT_BRAKE_SIGNAL = {CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G, CAR.HRV_3G} HONDA_BOSCH_RADARLESS = {CAR.CIVIC_2022, CAR.HRV_3G} diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index edc9e4855f..64a9fdf2ce 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -8,7 +8,7 @@ from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, \ - CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams + CANFD_CAR, Buttons, CarControllerParams from openpilot.selfdrive.car.interfaces import CarStateBase PREV_BUTTON_SAMPLES = 8 @@ -36,8 +36,8 @@ class CarState(CarStateBase): else: # preferred and elect gear methods use same definition self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] - self.accelerator_msg_canfd = "ACCELERATOR" if CP.carFingerprint in EV_CAR else \ - "ACCELERATOR_ALT" if CP.carFingerprint in HYBRID_CAR else \ + self.accelerator_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ + "ACCELERATOR_ALT" if CP.flags & HyundaiFlags.HYBRID else \ "ACCELERATOR_BRAKE_ALT" self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ "CRUISE_BUTTONS" @@ -120,8 +120,8 @@ class CarState(CarStateBase): ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - if self.CP.carFingerprint in (HYBRID_CAR | EV_CAR): - if self.CP.carFingerprint in HYBRID_CAR: + if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + if self.CP.flags & HyundaiFlags.HYBRID: ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. else: ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. @@ -132,7 +132,7 @@ class CarState(CarStateBase): # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, # as this seems to be standard over all cars, but is not the preferred method. - if self.CP.carFingerprint in (HYBRID_CAR | EV_CAR): + if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: gear = cp.vl["CLU15"]["CF_Clu_Gear"] @@ -147,8 +147,9 @@ class CarState(CarStateBase): aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12" aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct" aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 + scc_warning = cp_cruise.vl["SCC12"]["TakeOverReq"] == 1 # sometimes only SCC system shows an FCW aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 - ret.stockFcw = aeb_warning and not aeb_braking + ret.stockFcw = (aeb_warning or scc_warning) and not aeb_braking ret.stockAeb = aeb_warning and aeb_braking if self.CP.enableBsm: @@ -171,8 +172,8 @@ class CarState(CarStateBase): self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1 speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - if self.CP.carFingerprint in (EV_CAR | HYBRID_CAR): - offset = 255. if self.CP.carFingerprint in EV_CAR else 1023. + if self.CP.flags & (HyundaiFlags.EV | HyundaiFlags.HYBRID): + offset = 255. if self.CP.flags & HyundaiFlags.EV else 1023. ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset ret.gasPressed = ret.gas > 1e-5 else: @@ -232,7 +233,7 @@ class CarState(CarStateBase): # It limits the vehicle speed, overridable by pressing the accelerator past a certain point. # The car will brake, but does not respect positive acceleration commands in this mode # TODO: find this message on ICE & HYBRID cars + cruise control signals (if exists) - if self.CP.carFingerprint in EV_CAR: + if self.CP.flags & HyundaiFlags.EV: ret.cruiseState.nonAdaptive = cp.vl["MANUAL_SPEED_LIMIT_ASSIST"]["MSLA_ENABLED"] == 1 self.prev_cruise_buttons = self.cruise_buttons[-1] @@ -277,7 +278,7 @@ class CarState(CarStateBase): if CP.enableBsm: messages.append(("LCA11", 50)) - if CP.carFingerprint in (HYBRID_CAR | EV_CAR): + if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): messages.append(("E_EMS11", 50)) else: messages += [ @@ -285,7 +286,7 @@ class CarState(CarStateBase): ("EMS16", 100), ] - if CP.carFingerprint in (HYBRID_CAR | EV_CAR): + if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): messages.append(("ELECT_GEAR", 20)) elif CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: pass @@ -329,7 +330,7 @@ class CarState(CarStateBase): ("DOORS_SEATBELTS", 4), ] - if CP.carFingerprint in EV_CAR: + if CP.flags & HyundaiFlags.EV: messages += [ ("MANUAL_SPEED_LIMIT_ASSIST", 10), ] diff --git a/selfdrive/car/hyundai/fingerprints.py b/selfdrive/car/hyundai/fingerprints.py new file mode 100644 index 0000000000..d1fc1faabb --- /dev/null +++ b/selfdrive/car/hyundai/fingerprints.py @@ -0,0 +1,1710 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.hyundai.values import CAR + +Ecu = car.CarParams.Ecu + +FINGERPRINTS = { + CAR.HYUNDAI_GENESIS: [{ + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 + }, + { + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1378: 4, 1379: 8, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 + }, + { + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1268: 8, 1280: 1, 1281: 3, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1437: 8, 1456: 4 + }, + { + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1378: 4, 1379: 8, 1384: 5, 1407: 8, 1425: 2, 1427: 6, 1437: 8, 1456: 4 + }, + { + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1437: 8, 1456: 4 + }], + CAR.SANTA_FE: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8 + }, + { + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 764: 8, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1186: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 + }, + { + 67: 8, 68: 8, 80: 4, 160: 8, 161: 8, 272: 8, 288: 4, 339: 8, 356: 8, 357: 8, 399: 8, 544: 8, 608: 8, 672: 8, 688: 5, 704: 1, 790: 8, 809: 8, 848: 8, 880: 8, 898: 8, 900: 8, 901: 8, 904: 8, 1056: 8, 1064: 8, 1065: 8, 1072: 8, 1075: 8, 1087: 8, 1088: 8, 1151: 8, 1200: 8, 1201: 8, 1232: 4, 1264: 8, 1265: 8, 1266: 8, 1296: 8, 1306: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1348: 8, 1349: 8, 1369: 8, 1370: 8, 1371: 8, 1407: 8, 1415: 8, 1419: 8, 1440: 8, 1442: 4, 1461: 8, 1470: 8 + }], + CAR.SONATA: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 549: 8, 550: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1096: 8, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1379: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 + }], + CAR.SONATA_LF: [{ + 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1397: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2014: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.KIA_SORENTO: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 + }], + CAR.KIA_STINGER: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 + }], + CAR.GENESIS_G80: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1024: 2, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8 + }, + { + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 546: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1437: 8, 1456: 4, 1470: 8 + }, + { + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1162: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1193: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1437: 8, 1456: 4, 1470: 8 + }], + CAR.GENESIS_G90: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 + }], + CAR.IONIQ_EV_2020: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 + }], + CAR.IONIQ: [{ + 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 8, 576: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1473: 8, 1476: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 + }], + CAR.KONA_EV: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 1157: 4, 1193: 8, 1379: 8, 1988: 8, 1996: 8 + }], + CAR.KONA_EV_2022: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1069: 8, 1078: 4, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1173: 8, 1183: 8, 1188: 8, 1191: 2, 1193: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1339: 8, 1342: 8, 1343: 8, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1446: 8, 1456: 4, 1470: 8, 1473: 8, 1485: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8 + }], + CAR.KIA_NIRO_EV: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 + }], + CAR.KIA_OPTIMA_H: [{ + 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1236: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 + }, + { + 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1420: 8, 1425: 2, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 + }], + CAR.PALISADE: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 547: 8, 548: 8, 549: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1123: 8, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8 + }], +} + +FW_VERSIONS = { + CAR.AZERA_6TH_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 U912\x00\x00\x00\x00\x00\x00SIG0M35MH0\xa4 |.', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81641KA051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.AZERA_HEV_6TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.00 99211-G8000 180903', + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', + b'\xf1\x00IG MDPS C 1.00 1.01 56310M9350\x00 4IH8C101', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', + b'\xf1\x00IGhe SCC FHCUP 1.00 1.01 99110-M9000 ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006T7N0_C2\x00\x006T7Q2051\x00\x00TIG2H24KA2\x12@\x11\xb7', + b'\xf1\x006T7N0_C2\x00\x006T7VA051\x00\x00TIGSH24KA1\xc7\x85\xe2`', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H570051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H590051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.HYUNDAI_GENESIS: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DH LKAS 1.1 -150210', + b'\xf1\x00DH LKAS 1.4 -140110', + b'\xf1\x00DH LKAS 1.5 -140425', + ], + }, + CAR.IONIQ: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F2051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3H1051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H1051\x00\x00HAE0G16US2\x00\x00\x00\x00', + ], + }, + CAR.IONIQ_PHEV_2019: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PAE0G16NS1\x00\x00\x00\x00', + b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PAE0G16NS1\xdbD\r\x81', + ], + }, + CAR.IONIQ_PHEV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U3H1_C2\x00\x006U3J8051\x00\x00PAETG16UL0\x00\x00\x00\x00', + b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL0\x00\x00\x00\x00', + b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\xad\xeb\xabt', + b'\xf1\x816U3J8051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J8051\x00\x00PAETG16UL0\x00\x00\x00\x00', + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL0\x82zT\xd2', + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\x00\x00\x00\x00', + ], + }, + CAR.IONIQ_EV_2020: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7500 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2700 201027', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', + b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', + ], + }, + CAR.IONIQ_EV_LTD: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', + b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', + b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', + b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', + b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', + b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.IONIQ_HEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HAE0G16NL2\x96\xda\xd4\xee', + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HAE0G16NL2\x00\x00\x00\x00', + ], + }, + CAR.SONATA: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', + b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', + b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', + b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', + b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', + b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', + b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', + b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', + b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', + b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', + ], + (Ecu.engine, 0x7e0, None): [ + b'HM6M1_0a0_F00', + b'HM6M1_0a0_G20', + b'HM6M2_0a0_BD0', + b'\xf1\x81HM6M1_0a0_F00', + b'\xf1\x81HM6M1_0a0_G20', + b'\xf1\x82DNBVN5GMCCXXXDCA', + b'\xf1\x82DNBVN5GMCCXXXG2F', + b'\xf1\x82DNBWN5TMDCXXXG2E', + b'\xf1\x82DNCVN5GMCCXXXF0A', + b'\xf1\x82DNCVN5GMCCXXXG2B', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_J10', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82DNDWN5TMDCXXXJ1A', + b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M00', + b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M10', + b'\xf1\x8739110-2S042\xf1\x81HM6M1_0a0_M00', + b'\xf1\x8739110-2S278\xf1\x82DNDVD5GMCCXXXL5B', + b'\xf1\x87391162M003', + b'\xf1\x87391162M010', + b'\xf1\x87391162M013', + b'\xf1\x87391162M023', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', + b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', + b'\xf1\x8756310-L0010\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', + b'\xf1\x8756310-L0210\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', + b'\xf1\x8756310-L1010\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', + b'\xf1\x8756310-L1030\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', + b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', + b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', + b'\xf1\x8756310L0210\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', + b'\xf1\x8757700-L0000\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', + b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00HT6TA260BLHT6TA800A1TDN8C20KS4\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x00HT6TA260BLHT6TA810A1TDN8M25GS0\x00\x00\x00\x00\x00\x00\xaa\x8c\xd9p', + b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x96\xa1\xf1\x92', + b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB2\x00\x00\x00\x00\x00\x00\x08\xc9O:', + b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB4\x00\x00\x00\x00\x00\x00g!l[', + b'\xf1\x00HT6WA280BLHT6WAE10A1SDN8G25NB5\x00\x00\x00\x00\x00\x00\xe0t\xa9\xba', + b'\xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', + b'\xf1\x00T02601BL T02832A1 VDN8T25XXX832NS8G\x0e\xfeE', + b'\xf1\x00T02601BL T02900A1 VDN8T25XXX900NSA\xb9\x13\xf9p', + b'\xf1\x00T02601BL T02900A1 VDN8T25XXX900NSCF\xe4!Y', + b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16KB05\x95h%', + b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', + b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87954A02N060\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', + b'\xf1\x87SAKFBA2926554GJ2VefVww\x87xwwwww\x88\x87xww\x87wTo\xfb\xffvUo\xff\x8d\x16\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SAKFBA3030524GJ2UVugww\x97yx\x88\x87\x88vw\x87gww\x87wto\xf9\xfffUo\xff\xa2\x0c\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SAKFBA3356084GJ2\x86fvgUUuWgw\x86www\x87wffvf\xb6\xcf\xfc\xffeUO\xff\x12\x19\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SAKFBA3474944GJ2ffvgwwwwg\x88\x86x\x88\x88\x98\x88ffvfeo\xfa\xff\x86fo\xff\t\xae\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SAKFBA3475714GJ2Vfvgvg\x96yx\x88\x97\x88ww\x87ww\x88\x87xs_\xfb\xffvUO\xff\x0f\xff\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALDBA3510954GJ3ww\x87xUUuWx\x88\x87\x88\x87w\x88wvfwfc_\xf9\xff\x98wO\xffl\xe0\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA3573534GJ3\x89\x98\x89\x88EUuWgwvwwwwww\x88\x87xTo\xfa\xff\x86f\x7f\xffo\x0e\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA3601464GJ3\x88\x88\x88\x88ffvggwvwvw\x87gww\x87wvo\xfb\xff\x98\x88\x7f\xffjJ\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA3753044GJ3UUeVff\x86hwwwwvwwgvfgfvo\xf9\xfffU_\xffC\xae\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA3862294GJ3vfvgvefVxw\x87\x87w\x88\x87xwwwwc_\xf9\xff\x87w\x9f\xff\xd5\xdc\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA3873834GJ3fefVwuwWx\x88\x97\x88w\x88\x97xww\x87wU_\xfb\xff\x86f\x8f\xffN\x04\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA4525334GJ3\x89\x99\x99\x99fevWh\x88\x86\x88fwvgw\x88\x87xfo\xfa\xffuDo\xff\xd1>\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA4626804GJ3wwww\x88\x87\x88xx\x88\x87\x88wwgw\x88\x88\x98\x88\x95_\xf9\xffuDo\xff|\xe7\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA4803224GJ3wwwwwvwg\x88\x88\x98\x88wwww\x87\x88\x88xu\x9f\xfc\xff\x87f\x8f\xff\xea\xea\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA6212564GJ3\x87wwwUTuGg\x88\x86xx\x88\x87\x88\x87\x88\x98xu?\xf9\xff\x97f\x7f\xff\xb8\n\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA6347404GJ3wwwwff\x86hx\x88\x97\x88\x88\x88\x88\x88vfgf\x88?\xfc\xff\x86Uo\xff\xec/\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA6901634GJ3UUuWVeVUww\x87wwwwwvUge\x86/\xfb\xff\xbb\x99\x7f\xff]2\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALDBA7077724GJ3\x98\x88\x88\x88ww\x97ygwvwww\x87ww\x88\x87x\x87_\xfd\xff\xba\x99o\xff\x99\x01\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SALFBA3525114GJ2wvwgvfvggw\x86wffvffw\x86g\x85_\xf9\xff\xa8wo\xffv\xcd\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA3624024GJ2\x88\x88\x88\x88wv\x87hx\x88\x97\x88x\x88\x97\x88ww\x87w\x86o\xfa\xffvU\x7f\xff\xd1\xec\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA3960824GJ2wwwwff\x86hffvfffffvfwfg_\xf9\xff\xa9\x88\x8f\xffb\x99\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA4011074GJ2fgvwwv\x87hw\x88\x87xww\x87wwfgvu_\xfa\xffefo\xff\x87\xc0\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA4121304GJ2x\x87xwff\x86hwwwwww\x87wwwww\x84_\xfc\xff\x98\x88\x9f\xffi\xa6\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA4195874GJ2EVugvf\x86hgwvwww\x87wgw\x86wc_\xfb\xff\x98\x88\x8f\xff\xe23\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA4625294GJ2eVefeUeVx\x88\x97\x88wwwwwwww\xa7o\xfb\xffvw\x9f\xff\xee.\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA4728774GJ2vfvg\x87vwgww\x87ww\x88\x97xww\x87w\x86_\xfb\xffeD?\xffk0\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA5129064GJ2vfvgwv\x87hx\x88\x87\x88ww\x87www\x87wd_\xfa\xffvfo\xff\x1d\x00\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA5454914GJ2\x98\x88\x88\x88\x87vwgx\x88\x87\x88xww\x87ffvf\xa7\x7f\xf9\xff\xa8w\x7f\xff\x1b\x90\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA5987784GJ2UVugDDtGx\x88\x87\x88w\x88\x87xwwwwd/\xfb\xff\x97fO\xff\xb0h\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA5987864GJ2fgvwUUuWgwvw\x87wxwwwww\x84/\xfc\xff\x97w\x7f\xff\xdf\x1d\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA6337644GJ2vgvwwv\x87hgffvwwwwwwww\x85O\xfa\xff\xa7w\x7f\xff\xc5\xfc\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA6802004GJ2UUuWUUuWgw\x86www\x87www\x87w\x96?\xf9\xff\xa9\x88\x7f\xff\x9fK\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA6892284GJ233S5\x87w\x87xx\x88\x87\x88vwwgww\x87w\x84?\xfb\xff\x98\x88\x8f\xff*\x9e\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', + b'\xf1\x87SALFBA7005534GJ2eUuWfg\x86xxww\x87x\x88\x87\x88\x88w\x88\x87\x87O\xfc\xffuUO\xff\xa3k\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', + b'\xf1\x87SALFBA7152454GJ2gvwgFf\x86hx\x88\x87\x88vfWfffffd?\xfa\xff\xba\x88o\xff,\xcf\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', + b'\xf1\x87SALFBA7460044GJ2gx\x87\x88Vf\x86hx\x88\x87\x88wwwwgw\x86wd?\xfa\xff\x86U_\xff\xaf\x1f\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SALFBA7485034GJ2ww\x87xww\x87xfwvgwwwwvfgf\xa5/\xfc\xff\xa9w_\xff40\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SAMDBA7743924GJ3wwwwww\x87xgwvw\x88\x88\x88\x88wwww\x85_\xfa\xff\x86f\x7f\xff0\x9d\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB2\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SAMDBA7817334GJ3Vgvwvfvgww\x87wwwwwwfgv\x97O\xfd\xff\x88\x88o\xff\x8e\xeb\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB2\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SAMDBA8054504GJ3gw\x87xffvgffffwwwweUVUf?\xfc\xffvU_\xff\xddl\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB2\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SAMFB41553621GC7ww\x87xUU\x85Xvwwg\x88\x88\x88\x88wwgw\x86\xaf\xfb\xffuDo\xff\xaa\x8f\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SAMFB42555421GC7\x88\x88\x88\x88wvwgx\x88\x87\x88wwgw\x87wxw3\x8f\xfc\xff\x98f\x8f\xffga\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SAMFBA7978674GJ2gw\x87xgw\x97ywwwwvUGeUUeU\x87O\xfb\xff\x98w\x8f\xfffF\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SAMFBA8105254GJ2wx\x87\x88Vf\x86hx\x88\x87\x88wwwwwwww\x86O\xfa\xff\x99\x88\x7f\xffZG\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SAMFBA9283024GJ2wwwwEUuWwwgwwwwwwwww\x87/\xfb\xff\x98w\x8f\xff<\xd3\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SAMFBA9708354GJ2wwwwVf\x86h\x88wx\x87xww\x87\x88\x88\x88\x88w/\xfa\xff\x97w\x8f\xff\x86\xa0\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x87SANDB45316691GC6\x99\x99\x99\x99\x88\x88\xa8\x8avfwfwwww\x87wxwT\x9f\xfd\xff\x88wo\xff\x1c\xfa\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB3\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SANFB45889451GC7wx\x87\x88gw\x87x\x88\x88x\x88\x87wxw\x87wxw\x87\x8f\xfc\xffeU\x8f\xff+Q\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + ], + }, + CAR.SONATA_LF: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', + b'\xf1\x00LF ESC \x0c 11 \x17\x01\x13 58920-C2610', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81606D5051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81606D5K51\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81606G1051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', + b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5', + b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2\x00\x00\x00\x00', + b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm', + b'\xf1\x87LAJSG49645724HF0\x87x\x87\x88\x87www\x88\x99\xa8\x89\x88\x99\xa8\x89\x88\x99\xa8\x89S_\xfb\xff\x87f\x7f\xff^2\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm', + b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\x00\x00\x00\x00', + b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5', + b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24SL2n\x8d\xbe\xd8', + ], + }, + CAR.TUCSON: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', + b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81606G3051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x8971TLC2NAIDDIR002\xf1\x8271TLC2NAIDDIR002', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', + b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87KMLDCU585233TJ20wx\x87\x88x\x88\x98\x89vfwfwwww\x87f\x9f\xff\x98\xff\x7f\xf9\xf7s\xf1\x816T6G4051\x00\x00\xf1\x006T6J0_C2\x00\x006T6G4051\x00\x00TTL4G24NH2\x00\x00\x00\x00', + b'\xf1\x87LBJXAN202299KF22\x87x\x87\x88ww\x87xx\x88\x97\x88\x87\x88\x98x\x88\x99\x98\x89\x87o\xf6\xff\x87w\x7f\xff\x12\x9a\xf1\x81U083\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U083\x00\x00\x00\x00\x00\x00TTL2V20KL1\x8fRn\x8a', + ], + }, + CAR.SANTA_FE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', + b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', + b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', + b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', + b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', + b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', + b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', + b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', + b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', + b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81606EA051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81606G1051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81606G3051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', + b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', + b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', + b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', + b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00', + b'\xf1\x00bcsh8p54 U833\x00\x00\x00\x00\x00\x00TTM4V22US3_<]\xf1', + b'\xf1\x87LBJSGA7082574HG0\x87www\x98\x88\x88\x88\x99\xaa\xb9\x9afw\x86gx\x99\xa7\x89co\xf8\xffvU_\xffR\xaf\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2T20NS1\x00\xa6\xe0\x91', + b'\xf1\x87LBKSGA0458404HG0vfvg\x87www\x89\x99\xa8\x99y\xaa\xa7\x9ax\x88\xa7\x88t_\xf9\xff\x86w\x8f\xff\x15x\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2T20NS1\x00\x00\x00\x00', + b'\xf1\x87LDJUEA6010814HG1\x87w\x87x\x86gvw\x88\x88\x98\x88gw\x86wx\x88\x97\x88\x85o\xf8\xff\x86f_\xff\xd37\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS0\xf8\x19\x92g', + b'\xf1\x87LDJUEA6458264HG1ww\x87x\x97x\x87\x88\x88\x99\x98\x89g\x88\x86xw\x88\x97x\x86o\xf7\xffvw\x8f\xff3\x9a\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS0\xf8\x19\x92g', + b'\xf1\x87LDKUEA2045844HG1wwww\x98\x88x\x87\x88\x88\xa8\x88x\x99\x97\x89x\x88\xa7\x88U\x7f\xf8\xffvfO\xffC\x1e\xf1\x816W3E0051\x00\x00\xf1\x006W351_C2\x00\x006W3E0051\x00\x00TTM4T20NS3\x00\x00\x00\x00', + b'\xf1\x87LDKUEA9993304HG1\x87www\x97x\x87\x88\x99\x99\xa9\x99x\x99\xa7\x89w\x88\x97x\x86_\xf7\xffwwO\xffl#\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS1R\x7f\x90\n', + b'\xf1\x87LDLUEA6061564HG1\xa9\x99\x89\x98\x87wwwx\x88\x97\x88x\x99\xa7\x89x\x99\xa7\x89sO\xf9\xffvU_\xff<\xde\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS50\xcb\xc3\xed', + b'\xf1\x87LDLUEA6159884HG1\x88\x87hv\x99\x99y\x97\x89\xaa\xb8\x9ax\x99\x87\x89y\x99\xb7\x99\xa7?\xf7\xff\x97wo\xff\xf3\x05\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00', + b'\xf1\x87LDLUEA6852664HG1\x97wWu\x97www\x89\xaa\xc8\x9ax\x99\x97\x89x\x99\xa7\x89SO\xf7\xff\xa8\x88\x7f\xff\x03z\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS50\xcb\xc3\xed', + b'\xf1\x87LDLUEA6898374HG1fevW\x87wwwx\x88\x97\x88h\x88\x96\x88x\x88\xa7\x88ao\xf9\xff\x98\x99\x7f\xffD\xe2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00', + b'\xf1\x87LDLUEA6898374HG1fevW\x87wwwx\x88\x97\x88h\x88\x96\x88x\x88\xa7\x88ao\xf9\xff\x98\x99\x7f\xffD\xe2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS50\xcb\xc3\xed', + b'\xf1\x87SBJWAA5842214GG0\x88\x87\x88xww\x87x\x89\x99\xa8\x99\x88\x99\x98\x89w\x88\x87xw_\xfa\xfffU_\xff\xd1\x8d\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x98{|\xe3', + b'\xf1\x87SBJWAA5890864GG0\xa9\x99\x89\x98\x98\x87\x98y\x89\x99\xa8\x99w\x88\x87xww\x87wvo\xfb\xffuD_\xff\x9f\xb5\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x98{|\xe3', + b'\xf1\x87SBJWAA6562474GG0ffvgeTeFx\x88\x97\x88ww\x87www\x87w\x84o\xfa\xff\x87fO\xff\xc2 \xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x00\x00\x00\x00', + b'\xf1\x87SBJWAA6562474GG0ffvgeTeFx\x88\x97\x88ww\x87www\x87w\x84o\xfa\xff\x87fO\xff\xc2 \xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x98{|\xe3', + b'\xf1\x87SBJWAA7780564GG0wvwgUUeVwwwwx\x88\x87\x88wwwwd_\xfc\xff\x86f\x7f\xff\xd7*\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS2F\x84<\xc0', + b'\xf1\x87SBJWAA8278284GG0ffvgUU\x85Xx\x88\x87\x88x\x88w\x88ww\x87w\x96o\xfd\xff\xa7U_\xff\xf2\xa0\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS2F\x84<\xc0', + b'\xf1\x87SBLWAA4363244GG0wvwgwv\x87hgw\x86ww\x88\x87xww\x87wdo\xfb\xff\x86f\x7f\xff3$\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS6\x00\x00\x00\x00', + b'\xf1\x87SBLWAA4363244GG0wvwgwv\x87hgw\x86ww\x88\x87xww\x87wdo\xfb\xff\x86f\x7f\xff3$\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS6x0\x17\xfe', + b'\xf1\x87SBLWAA4899564GG0VfvgUU\x85Xx\x88\x87\x88vfgf\x87wxwvO\xfb\xff\x97f\xb1\xffSB\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS7\x00\x00\x00\x00', + b'\xf1\x87SBLWAA6622844GG0wwwwff\x86hwwwwx\x88\x87\x88\x88\x88\x88\x88\x98?\xfd\xff\xa9\x88\x7f\xffn\xe5\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS7u\x1e{\x1c', + b'\xf1\x87SDJXAA7656854GG1DEtWUU\x85X\x88\x88\x98\x88w\x88\x87xx\x88\x87\x88\x96o\xfb\xff\x86f\x7f\xff.\xca\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4G24NS2\x00\x00\x00\x00', + b'\xf1\x87SDJXAA7656854GG1DEtWUU\x85X\x88\x88\x98\x88w\x88\x87xx\x88\x87\x88\x96o\xfb\xff\x86f\x7f\xff.\xca\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4G24NS2K\xdaV0', + b'\xf1\x87SDKXAA2443414GG1vfvgwv\x87h\x88\x88\x88\x88ww\x87wwwww\x99_\xfc\xffvD?\xffl\xd2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4G24NS6\x00\x00\x00\x00', + ], + }, + CAR.SANTA_FE_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', + b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', + b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', + b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', + b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', + b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', + b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', + b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', + b'\xf1\x8758910-S1DA0\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', + b'\xf1\x8758910-S2DA0\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', + b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', + b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81HM6M1_0a0_G20', + b'\xf1\x81HM6M1_0a0_H00', + b'\xf1\x81HM6M2_0a0_G00', + b'\xf1\x82TACVN5GMI3XXXH0A', + b'\xf1\x82TACVN5GSI3XXXH0A', + b'\xf1\x82TMBZN5TMD3XXXG2E', + b'\xf1\x82TMCFD5MMCXXXXG0A', + b'\xf1\x87 \xf1\x81 ', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_J10', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_L50', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82TMDWN5TMD3TXXJ1A', + b'\xf1\x8739101-2STN8\xf1\x81HM6M1_0a0_M00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', + b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00HT6TA290BLHT6TAF00A1STM0M25GS1\x00\x00\x00\x00\x00\x006\xd8\x97\x15', + b'\xf1\x00HT6WA280BLHT6WAD00A1STM2G25NH2\x00\x00\x00\x00\x00\x00\xf8\xc0\xc3\xaa', + b'\xf1\x00HT6WA280BLHT6WAD00A1STM4G25NH1\x00\x00\x00\x00\x00\x00\x9cl\x04\xbc', + b'\xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7', + b'\xf1\x00T02601BL T02800A1 VTMPT25XXX800NS4\xed\xaf\xed\xf5', + b'\xf1\x00T02601BL T02900A1 VTMPT25XXW900NS1c\x918\xc5', + b'\xf1\x00T02601BL T02900A1 VTMPT25XXX900NS8\xb7\xaa\xfe\xfc', + b'\xf1\x00T02601BL T02900A1 VTMPT25XXX900NSA\xf3\xf4Uj', + b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6', + b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7', + b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02900A1 \xf1\x00T02601BL T02900A1 VTMPT25XXX900NS8\xb7\xaa\xfe\xfc', + b'\xf1\x87KMMYBU034207SB72x\x89\x88\x98h\x88\x98\x89\x87fhvvfWf33_\xff\x87\xff\x8f\xfa\x81\xe5\xf1\x89HT6TAF00A1\xf1\x82STM0M25GS1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SDMXCA8653204GN1EVugEUuWwwwwww\x87wwwwwv/\xfb\xff\xa8\x88\x9f\xff\xa5\x9c\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00', + b'\xf1\x87SDMXCA9087684GN1VfvgUUeVwwgwwwwwffffU?\xfb\xff\x97\x88\x7f\xff+\xa4\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.SANTA_FE_HEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', + b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', + b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2H16SA3\xa3\x1b\xe14', + b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2H16UA3I\x94\xac\x8f', + b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TTM2H16SA2\x80\xd7l\xb2', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391312MTC1', + b'\xf1\x87391312MTE0', + b'\xf1\x87391312MTL0', + ], + }, + CAR.SANTA_FE_PHEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', + b'\xf1\x8799110CL500\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA1\x0b\xc5\x0f\xea', + b'\xf1\x8795441-3D121\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA0o\x88^\xbe', + b'\xf1\x8795441-3D121\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA1\x0b\xc5\x0f\xea', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391312MTF0', + b'\xf1\x87391312MTF1', + ], + }, + CAR.CUSTIN_1ST_GEN: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391212MEC0', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 U928\x00\x00\x00\x00\x00\x00SKU0T15KB2\x92U\xf9M', + ], + }, + CAR.KIA_STINGER: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xe0\x19\xff\xe7\xe7g\x01\xa2\x00\x0f\x00\x9e\x00\x06\x00\xff\xff\xff\xff\xff\xff\x00\x00\xff\xff\xff\xff\xff\xff\x00\x00\x0f\x0e\x0f\x0f\x0e\r\x00\x00\x7f\x02.\xff\x00\x00~p\x00\x00\x00\x00u\xff\xf9\xff\x00\x00\x00\x00V\t\xd5\x01\xc0\x00\x00\x00\x007\xfb\xfc\x0b\x8d\x00', + b'\xf1\x81606DE051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640E0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x82CKJN3TMSDE0B\x00\x00\x00\x00', + b'\xf1\x82CKKN3TMD_H0A\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', + b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', + b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', + b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\t\xb7\x17\xf5', + b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SCK0T33NB2\xb3\xee\xba\xdc', + b'\xf1\x87VCJLE17622572DK0vd6D\x99\x98y\x97vwVffUfvfC%CuT&Dx\x87o\xff{\x1c\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\t\xb7\x17\xf5', + b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x89E21\x00\x00\x00\x00\x00\x00\x00\xf1\x82SCK0T33NB0', + b'\xf1\x87VDHLG17034412DK2vD6DfVvVTD$D\x99w\x88\x98EDEDeT6DgfO\xff\xc3=\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', + b'\xf1\x87VDHLG17274082DK2wfFf\x89x\x98wUT5T\x88v\x97xgeGefTGTVvO\xff\x1c\x14\xf1\x81E19\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E19\x00\x00\x00\x00\x00\x00\x00SCK0T33UB2\xee[\x97S', + b'\xf1\x87VDKLJ18675252DK6\x89vhgwwwwveVU\x88w\x87w\x99vgf\x97vXfgw_\xff\xc2\xfb\xf1\x89E25\x00\x00\x00\x00\x00\x00\x00\xf1\x82TCK0T33NB2', + b'\xf1\x87WAJTE17552812CH4vfFffvfVeT5DwvvVVdFeegeg\x88\x88o\xff\x1a]\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00TCK2T20NB1\x19\xd2\x00\x94', + ], + }, + CAR.KIA_STINGER_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.01 99110-J5100 ', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81640N2051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640R0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81HM6M1_0a0_H00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5320 4C2VL503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', + b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 99211-J5000 201209', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 E31\x00\x00\x00\x00\x00\x00\x00SCK0T25KH2B\xfbI\xe2', + b'\xf1\x00bcsh8p54 E31\x00\x00\x00\x00\x00\x00\x00SCK0T33NH07\xdf\xf0\xc1', + b'\xf1\x00bcsh8p54 E31\x00\x00\x00\x00\x00\x00\x00TCK0T33NH0%g~\xd3', + b'\xf1\x87VCNLF11383972DK1vffV\x99\x99\x89\x98\x86eUU\x88wg\x89vfff\x97fff\x99\x87o\xff"\xc1\xf1\x81E30\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E30\x00\x00\x00\x00\x00\x00\x00SCK0T33GH0\xbe`\xfb\xc6', + ], + }, + CAR.PALISADE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', + b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', + b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', + b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', + b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', + b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', + b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640K0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640S1051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', + b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', + b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', + b'\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00TON2G38NB5j\x94.\xde', + b'\xf1\x87LBLUFN591307KF25vgvw\x97wwwy\x99\xa7\x99\x99\xaa\xa9\x9af\x88\x96h\x95o\xf7\xff\x99f/\xff\xe4c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB2\xd7\xc1/\xd1', + b"\xf1\x87LBLUFN622950KF36\xa8\x88\x88\x88\x87w\x87xh\x99\x96\x89\x88\x99\x98\x89\x88\x99\x98\x89\x87o\xf6\xff\x98\x88o\xffx'\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8", + b'\xf1\x87LBLUFN650868KF36\xa9\x98\x89\x88\xa8\x88\x88\x88h\x99\xa6\x89fw\x86gw\x88\x97x\xaa\x7f\xf6\xff\xbb\xbb\x8f\xff+\x82\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', + b'\xf1\x87LBLUFN655162KF36\x98\x88\x88\x88\x98\x88\x88\x88x\x99\xa7\x89x\x99\xa7\x89x\x99\x97\x89g\x7f\xf7\xffwU_\xff\xe9!\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', + b'\xf1\x87LBLUFN731381KF36\xb9\x99\x89\x98\x98\x88\x88\x88\x89\x99\xa8\x99\x88\x99\xa8\x89\x88\x88\x98\x88V\x7f\xf6\xff\x99w\x8f\xff\xad\xd8\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', + b'\xf1\x87LDKVAA0028604HH1\xa8\x88x\x87vgvw\x88\x99\xa8\x89gw\x86ww\x88\x97x\x97o\xf9\xff\x97w\x7f\xffo\x02\xf1\x81U872\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', + b'\xf1\x87LDKVAA3068374HH1wwww\x87xw\x87y\x99\xa7\x99w\x88\x87xw\x88\x97x\x85\xaf\xfa\xffvU/\xffU\xdc\xf1\x81U872\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', + b'\xf1\x87LDKVBN382172KF26\x98\x88\x88\x88\xa8\x88\x88\x88x\x99\xa7\x89\x87\x88\x98x\x98\x99\xa9\x89\xa5_\xf6\xffDDO\xff\xcd\x16\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', + b'\xf1\x87LDKVBN424201KF26\xba\xaa\x9a\xa9\x99\x99\x89\x98\x89\x99\xa8\x99\x88\x99\x98\x89\x88\x99\xa8\x89v\x7f\xf7\xffwf_\xffq\xa6\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', + b'\xf1\x87LDKVBN540766KF37\x87wgv\x87w\x87xx\x99\x97\x89v\x88\x97h\x88\x88\x88\x88x\x7f\xf6\xffvUo\xff\xd3\x01\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', + b'\xf1\x87LDLVAA4225634HH1\x98\x88\x88\x88eUeVx\x88\x87\x88g\x88\x86xx\x88\x87\x88\x86o\xf9\xff\x87w\x7f\xff\xf2\xf7\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x87LDLVAA4478824HH1\x87wwwvfvg\x89\x99\xa8\x99w\x88\x87x\x89\x99\xa8\x99\xa6o\xfa\xfffU/\xffu\x92\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x87LDLVAA4777834HH1\x98\x88x\x87\x87wwwx\x88\x87\x88x\x99\x97\x89x\x88\x97\x88\x86o\xfa\xff\x86fO\xff\x1d9\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x87LDLVAA5194534HH1ffvguUUUx\x88\xa7\x88h\x99\x96\x89x\x88\x97\x88ro\xf9\xff\x98wo\xff\xaaM\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x87LDLVAA5949924HH1\xa9\x99y\x97\x87wwwx\x99\x97\x89x\x99\xa7\x89x\x99\xa7\x89\x87_\xfa\xffeD?\xff\xf1\xfd\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x87LDLVBN560098KF26\x86fff\x87vgfg\x88\x96xfw\x86gfw\x86g\x95\xf6\xffeU_\xff\x92c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', + b'\xf1\x87LDLVBN602045KF26\xb9\x99\x89\x98\x97vwgy\xaa\xb7\x9af\x88\x96hw\x99\xa7y\xa9\x7f\xf5\xff\x99w\x7f\xff,\xd3\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN628911KF26\xa9\x99\x89\x98\x98\x88\x88\x88y\x99\xa7\x99fw\x86gw\x88\x87x\x83\x7f\xf6\xff\x98wo\xff2\xda\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN645817KF37\x87www\x98\x87xwx\x99\x97\x89\x99\x99\x99\x99g\x88\x96x\xb6_\xf7\xff\x98fo\xff\xe2\x86\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN662115KF37\x98\x88\x88\x88\xa8\x88\x88\x88x\x99\x97\x89x\x99\xa7\x89\x88\x99\xa8\x89\x88\x7f\xf7\xfffD_\xff\xdc\x84\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN667933KF37\xb9\x99\x89\x98\xb9\x99\x99\x99x\x88\x87\x88w\x88\x87x\x88\x88\x98\x88\xcbo\xf7\xffe3/\xffQ!\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN673087KF37\x97www\x86fvgx\x99\x97\x89\x99\xaa\xa9\x9ag\x88\x86x\xe9_\xf8\xff\x98w\x7f\xff"\xad\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN673841KF37\x98\x88x\x87\x86g\x86xy\x99\xa7\x99\x88\x99\xa8\x89w\x88\x97xdo\xf5\xff\x98\x88\x8f\xffT\xec\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN681363KF37\x98\x88\x88\x88\x97x\x87\x88y\xaa\xa7\x9a\x88\x88\x98\x88\x88\x88\x88\x88vo\xf6\xffvD\x7f\xff%v\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN713782KF37\x99\x99y\x97\x98\x88\x88\x88x\x88\x97\x88\x88\x99\x98\x89\x88\x99\xa8\x89\x87o\xf7\xffeU?\xff7,\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN713890KF26\xb9\x99\x89\x98\xa9\x99\x99\x99x\x99\x97\x89\x88\x99\xa8\x89\x88\x99\xb8\x89Do\xf7\xff\xa9\x88o\xffs\r\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN733215KF37\x99\x98y\x87\x97wwwi\x99\xa6\x99x\x99\xa7\x89V\x88\x95h\x86o\xf7\xffeDO\xff\x12\xe7\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN750044KF37\xca\xa9\x8a\x98\xa7wwwy\xaa\xb7\x9ag\x88\x96x\x88\x99\xa8\x89\xb9\x7f\xf6\xff\xa8w\x7f\xff\xbe\xde\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN752612KF37\xba\xaa\x8a\xa8\x87w\x87xy\xaa\xa7\x9a\x88\x99\x98\x89x\x88\x97\x88\x96o\xf6\xffvU_\xffh\x1b\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN755553KF37\x87xw\x87\x97w\x87xy\x99\xa7\x99\x99\x99\xa9\x99Vw\x95gwo\xf6\xffwUO\xff\xb5T\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', + b'\xf1\x87LDLVBN757883KF37\x98\x87xw\x98\x87\x88xy\xaa\xb7\x9ag\x88\x96x\x89\x99\xa8\x99e\x7f\xf6\xff\xa9\x88o\xff5\x15\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', + b'\xf1\x87LDMVBN778156KF37\x87vWe\xa9\x99\x99\x99y\x99\xb7\x99\x99\x99\x99\x99x\x99\x97\x89\xa8\x7f\xf8\xffwf\x7f\xff\x82_\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', + b'\xf1\x87LDMVBN780576KF37\x98\x87hv\x97x\x97\x89x\x99\xa7\x89\x88\x99\x98\x89w\x88\x97x\x98\x7f\xf7\xff\xba\x88\x8f\xff\x1e0\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', + b'\xf1\x87LDMVBN783485KF37\x87www\x87vwgy\x99\xa7\x99\x99\x99\xa9\x99Vw\x95g\x89_\xf6\xff\xa9w_\xff\xc5\xd6\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', + b'\xf1\x87LDMVBN811844KF37\x87vwgvfffx\x99\xa7\x89Vw\x95gg\x88\xa6xe\x8f\xf6\xff\x97wO\xff\t\x80\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', + b'\xf1\x87LDMVBN830601KF37\xa7www\xa8\x87xwx\x99\xa7\x89Uw\x85Ww\x88\x97x\x88o\xf6\xff\x8a\xaa\x7f\xff\xe2:\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', + b'\xf1\x87LDMVBN848789KF37\x87w\x87x\x87w\x87xy\x99\xb7\x99\x87\x88\x98x\x88\x99\xa8\x89\x87\x7f\xf6\xfffUo\xff\xe3!\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN851595KF37\x97wgvvfffx\x99\xb7\x89\x88\x99\x98\x89\x87\x88\x98x\x99\x7f\xf7\xff\x97w\x7f\xff@\xf3\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN871852KF37\xb9\x99\x99\x99\xa8\x88\x88\x88y\x99\xa7\x99x\x99\xa7\x89\x88\x88\x98\x88\x89o\xf7\xff\xaa\x88o\xff\x0e\xed\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN873175KF26\xa8\x88\x88\x88vfVex\x99\xb7\x89\x88\x99\x98\x89x\x88\x97\x88f\x7f\xf7\xff\xbb\xaa\x8f\xff,\x04\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN879401KF26veVU\xa8\x88\x88\x88g\x88\xa6xVw\x95gx\x88\xa7\x88v\x8f\xf9\xff\xdd\xbb\xbf\xff\xb3\x99\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN881314KF37\xa8\x88h\x86\x97www\x89\x99\xa8\x99w\x88\x97xx\x99\xa7\x89\xca\x7f\xf8\xff\xba\x99\x8f\xff\xd8v\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN888651KF37\xa9\x99\x89\x98vfff\x88\x99\x98\x89w\x99\xa7y\x88\x88\x98\x88D\x8f\xf9\xff\xcb\x99\x8f\xff\xa5\x1e\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN889419KF37\xa9\x99y\x97\x87w\x87xx\x88\x97\x88w\x88\x97x\x88\x99\x98\x89e\x9f\xf9\xffeUo\xff\x901\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN895969KF37vefV\x87vgfx\x99\xa7\x89\x99\x99\xb9\x99f\x88\x96he_\xf7\xffxwo\xff\x14\xf9\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN899222KF37\xa8\x88x\x87\x97www\x98\x99\x99\x89\x88\x99\x98\x89f\x88\x96hdo\xf7\xff\xbb\xaa\x9f\xff\xe2U\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + b'\xf1\x87LDMVBN950669KF37\x97www\x96fffy\x99\xa7\x99\xa9\x99\xaa\x99g\x88\x96x\xb8\x8f\xf9\xffTD/\xff\xa7\xcb\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', + ], + }, + CAR.VELOSTER: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', + b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816V8RAC00121.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x01TJS-JDK06F200H0A', + b'\x01TJS-JNU06F200H0A', + b'391282BJF5 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', + b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16KS2\x0e\xba\x1e\xa2', + b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\x00\x00\x00\x00', + b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\xba\x02\xb8\x80', + ], + }, + CAR.GENESIS_G70: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB2\x11\x1am\xda', + b'\xf1\x87VDJLT17895112DN4\x88fVf\x99\x88\x88\x88\x87fVe\x88vhwwUFU\x97eFex\x99\x7f\xff\xb7\x82\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB2\x11\x1am\xda', + ], + }, + CAR.GENESIS_G70_2020: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', + b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', + b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', + b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB4\xecE\xefL', + b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T20KB3Wuvz', + b'\xf1\x87VCJLP18407832DN3\x88vXfvUVT\x97eFU\x87d7v\x88eVeveFU\x89\x98\x7f\xff\xb2\xb0\xf1\x81E25\x00\x00\x00', + b'\xf1\x87VDJLC18480772DK9\x88eHfwfff\x87eFUeDEU\x98eFe\x86T5DVyo\xff\x87s\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33KB5\x9f\xa5&\x81', + b'\xf1\x87VDKLT18912362DN4wfVfwefeveVUwfvw\x88vWfvUFU\x89\xa9\x8f\xff\x87w\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB4\xecE\xefL', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', + b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', + b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81606G2051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.GENESIS_G80: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', + b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0G33KH2\xae\xde\xd5!', + b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0G38NH2j\x9dA\x1c', + b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0T33NH3\x97\xe6\xbc\xb8', + b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00TDH0G38NH3:-\xa9n', + b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SDH0T33NH4\xd7O\x9e\xc9', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81640A4051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.GENESIS_G90: { + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87VDGMD15352242DD3w\x87gxwvgv\x87wvw\x88wXwffVfffUfw\x88o\xff\x06J\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcshcm49 E14\x00\x00\x00\x00\x00\x00\x00SHI0G50NB1tc5\xb7', + b'\xf1\x87VDGMD15866192DD3x\x88x\x89wuFvvfUf\x88vWwgwwwvfVgx\x87o\xff\xbc^\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcshcm49 E14\x00\x00\x00\x00\x00\x00\x00SHI0G50NB1tc5\xb7', + b'\xf1\x87VDHMD16446682DD3WwwxxvGw\x88\x88\x87\x88\x88whxx\x87\x87\x87\x85fUfwu_\xffT\xf8\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcshcm49 E14\x00\x00\x00\x00\x00\x00\x00SHI0G50NB1tc5\xb7', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x810000000000\x00', + ], + }, + CAR.KONA: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'"\x01TOS-0NU06F301J02', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U2VE051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VE051\x00\x00DOS4T16NS3\x00\x00\x00\x00', + ], + }, + CAR.KIA_CEED: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x01TCD-JECU4F202H0K', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U2V7051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V7051\x00\x00DCD0T14US1\x00\x00\x00\x00', + b'\xf1\x816U2V7051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V7051\x00\x00DCD0T14US1U\x867Z', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CD ESC \x03 102\x18\x08\x05 58920-J7350', + ], + }, + CAR.KIA_FORTE: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', + b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', + b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', + b'\xf1\x00BDm MDPS C A.01 1.01 56310M7800\x00 4BPMC101', + b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', + b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x01TBDM1NU06F200H01', + b'391182B945\x00', + b'\xf1\x81616F2051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816VGRAH00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x8758900-M7AB0 \xf1\x816VQRAD00127.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006V2B0_C2\x00\x006V2C6051\x00\x00CBD0N20NL1\x00\x00\x00\x00', + b'\xf1\x006V2B0_C2\x00\x006V2C6051\x00\x00CBD0N20NL1\x90@\xc6\xae', + b'\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DBD0T16SS0\x00\x00\x00\x00', + b"\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DBD0T16SS0\xcf\x1e'\xc3", + ], + }, + CAR.KIA_K5_2021: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', + b'\xf1\x8799110L2000\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', + b'\xf1\x8799110L2100\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', + b'\xf1\x8799110L2100\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', + b'\xf1\x8756310-L3110\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', + b'\xf1\x8756310-L3220\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', + b'\xf1\x8757700-L3000\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', + b'\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', + b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', + b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', + b'\xf1\x8758910-L3200\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', + b'\xf1\x8758910-L3600\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', + b'\xf1\x8758910-L3800\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81HM6M2_0a0_DQ0', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82DLDWN5TMDCXXXJ1B', + b'\xf1\x87391212MKT0', + b'\xf1\x87391212MKT3', + b'\xf1\x87391212MKV0', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00HT6TA261BLHT6TAB00A1SDL0C20KS0\x00\x00\x00\x00\x00\x00\\\x9f\xa5\x15', + b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB1ia\x0b\xb8', + b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB2.\x13\xf6\xed', + b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL4T16NB05\x94t\x18', + b'\xf1\x87954A02N300\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 WDL3T25XXX730NS2b\x1f\xb8%', + b'\xf1\x87SALFEA5652514GK2UUeV\x88\x87\x88xxwg\x87ww\x87wwfwvd/\xfb\xffvU_\xff\x93\xd3\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB1ia\x0b\xb8', + b'\xf1\x87SALFEA6046104GK2wvwgeTeFg\x88\x96xwwwwffvfe?\xfd\xff\x86fo\xff\x97A\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB1ia\x0b\xb8', + b'\xf1\x87SCMSAA8572454GK1\x87x\x87\x88Vf\x86hgwvwvwwgvwwgT?\xfb\xff\x97fo\xffH\xb8\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL4T16NB05\x94t\x18', + ], + }, + CAR.KIA_K5_HEV_2020: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391162JLA0', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00PSBG2323 E08\x00\x00\x00\x00\x00\x00\x00TDL2H20KA2\xe3\xc6cz', + b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDL2H20KA5T\xf2\xc9\xc2', + ], + }, + CAR.KONA_EV: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', + b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', + b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', + b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', + b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', + b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', + b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', + ], + }, + CAR.KONA_EV_2022: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', + b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', + b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', + b'\xf1\x8758520-K4010\xf1\x00OS IEB \x02 101 \x11\x13 58520-K4010', + b'\xf1\x8758520-K4010\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', + b'\xf1\x8758520-K4010\xf1\x00OS IEB \x04 101 \x11\x13 58520-K4010', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', + b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', + b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', + ], + }, + CAR.KONA_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', + ], + }, + CAR.KIA_NIRO_EV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', + b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', + b'\xf1\x8799110Q4000\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', + b'\xf1\x8799110Q4100\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', + b'\xf1\x8799110Q4500\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', + b'\xf1\x8799110Q4600\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x8799110Q4600\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x8799110Q4600\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', + b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', + b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', + ], + }, + CAR.KIA_NIRO_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', + b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + ], + }, + CAR.KIA_NIRO_PHEV: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PDE0G16NL2&[\xc3\x01', + b'\xf1\x816U3H3051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H3051\x00\x00PDE0G16NS1\x00\x00\x00\x00', + b'\xf1\x816U3H3051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H3051\x00\x00PDE0G16NS1\x13\xcd\x88\x92', + b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\x00\x00\x00\x00', + b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91", + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', + b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', + ], + }, + CAR.KIA_NIRO_PHEV_2022: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PDE0G16NL3\x00\x00\x00\x00', + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PDE0G16NL3\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 99211-G5500 210428', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.06 99211-G5000 201028', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC F-CUP 1.00 1.00 99110-G5600 ', + ], + }, + CAR.KIA_NIRO_HEV_2021: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HDE0G16NL3\x00\x00\x00\x00', + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HDE0G16NL3\xb9\xd3\xfaW', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', + ], + }, + CAR.KIA_SELTOS: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x8799110Q5100\xf1\x00SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x8758910-Q5450\xf1\x00SP ESC \x07 101\x19\t\x05 58910-Q5450', + b'\xf1\x8758910-Q5450\xf1\x00SP ESC \t 101\x19\t\x05 58910-Q5450', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x01TSP2KNL06F100J0K', + b'\x01TSP2KNL06F200J0K', + b'\xf1\x81616D2051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81616D5051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00SP2 MDPS C 1.00 1.04 56300Q5200 ', + b'\xf1\x00SP2 MDPS C 1.01 1.05 56300Q5200 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', + b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\x00T0190XBL T01950A1 DSP2T16X4X950NS6\xd30\xa5\xb9', + b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\x00T0190XBL T01950A1 DSP2T16X4X950NS8\r\xfe\x9c\x8b', + b'\xf1\x87CZLUB49370612JF7h\xa8y\x87\x99\xa7hv\x99\x97fv\x88\x87x\x89x\x96O\xff\x88\xff\xff\xff.@\xf1\x816V2C2051\x00\x00\xf1\x006V2B0_C2\x00\x006V2C2051\x00\x00CSP4N20NS3\x00\x00\x00\x00', + ], + }, + CAR.KIA_OPTIMA_G4: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6J0051\x00\x00\xf1\x006T6J0_C2\x00\x006T6J0051\x00\x00TJF0T20NSB\x00\x00\x00\x00', + ], + }, + CAR.KIA_OPTIMA_G4_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', + ], + (Ecu.abs, 0x7d1, None): [ + b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", + b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', + b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW', + b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\x00\x00\x00\x00', + b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\xca3\xeb.', + b'\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DJF0T16NL2\x9eA\x80\x01', + b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW', + b'\xf1\x816U2VA051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\x00\x00\x00\x00', + b'\xf1\x816U2VA051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\xca3\xeb.', + b'\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DJF0T16NL2\x9eA\x80\x01', + b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B8051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B8051\x00\x00TJFSG24NH27\xa7\xc2\xb4', + ], + }, + CAR.KIA_OPTIMA_H: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', + ], + }, + CAR.KIA_OPTIMA_H_G4_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.ELANTRA: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', + b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006T6J0_C2\x00\x006T6F0051\x00\x00TAD0N20NS2\x00\x00\x00\x00', + b'\xf1\x006T6J0_C2\x00\x006T6F0051\x00\x00TAD0N20NS2\xc5\x92\x9e\x8a', + b'\xf1\x006T6J0_C2\x00\x006T6F0051\x00\x00TAD0N20SS2.~\x90\x87', + b'\xf1\x006T6K0_C2\x00\x006T6S2051\x00\x00TAD0N20NSD\x00\x00\x00\x00', + b'\xf1\x006T6K0_C2\x00\x006T6S2051\x00\x00TAD0N20NSD(\xfcA\x9d', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8161657051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816165D051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816165E051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x8161698051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', + b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', + b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', + ], + }, + CAR.ELANTRA_GT_I30: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', + b'\xf1\x00PD LKAS AT USA LHD 1.00 1.02 95740-G3000 A51', + b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U2U0_C2\x00\x006U2T0051\x00\x00DPD0D16KS0u\xce\x1fk', + b'\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DPD0T16NS4\x00\x00\x00\x00', + b'\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DPD0T16NS4\xda\x7f\xd6\xa7', + b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DPD0H16NS0e\x0e\xcd\x8e', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', + b'\xf1\x00PD MDPS C 1.00 1.03 56310/G3300 4PDDC103', + b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', + b'\xf1\x00PD ESC \x0b 103\x17\x110 58920-G3350', + b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', + b'\xf1\x00PD__ SCC F-CUP 1.01 1.00 96400-G3100 ', + b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', + ], + }, + CAR.ELANTRA_2021: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', + b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', + b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', + b'\xf1\x8799110AA000\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', + b'\xf1\x8799110AA000\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', + b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', + b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', + b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800\xf1\xa01.01', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\xe8\xba\xce\xfa', + b'\xf1\x87CXLQF40189012JL2f\x88\x86\x88\x88vUex\xb8\x88\x88\x88\x87\x88\x89fh?\xffz\xff\xff\xff\x08z\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', + b'\xf1\x87CXMQFM1916035JB2\x88vvgg\x87Wuwgev\xa9\x98\x88\x98h\x99\x9f\xffh\xff\xff\xff\xa5\xee\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', + b'\xf1\x87CXMQFM2135005JB2E\xb9\x89\x98W\xa9y\x97h\xa9\x98\x99wxvwh\x87\x7f\xffx\xff\xff\xff,,\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', + b'\xf1\x87CXMQFM2728305JB2E\x97\x87xw\x87vwgw\x84x\x88\x88w\x89EI\xbf\xff{\xff\xff\xff\xe6\x0e\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', + b'\xf1\x87CXMQFM3806705JB2\x89\x87wwx\x88g\x86\x99\x87\x86xwwv\x88yv\x7f\xffz\xff\xff\xffV\x15\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81HM6M2_0a0_FF0', + b'\xf1\x82CNCVD0AMFCXCSFFB', + b'\xf1\x82CNCWD0AMFCXCSFFA', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_G80', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_HC0', + ], + }, + CAR.ELANTRA_HEV_2021: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', + b'\xf1\x8799110BY000\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', + b'\xf1\x8756310/BY050\xf1\x00CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', + b'\xf1\x8756310/BY050\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U3L0_C2\x00\x006U3K3051\x00\x00HCN0G16NS0\x00\x00\x00\x00', + b'\xf1\x006U3L0_C2\x00\x006U3K3051\x00\x00HCN0G16NS0\xb9?A\xaa', + b'\xf1\x006U3L0_C2\x00\x006U3K9051\x00\x00HCN0G16NS1\x00\x00\x00\x00', + b'\xf1\x816U3K3051\x00\x00\xf1\x006U3L0_C2\x00\x006U3K3051\x00\x00HCN0G16NS0\x00\x00\x00\x00', + b'\xf1\x816U3K3051\x00\x00\xf1\x006U3L0_C2\x00\x006U3K3051\x00\x00HCN0G16NS0\xb9?A\xaa', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x816H6G8051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.KONA_HEV: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HOS0G16DS1\x16\xc7\xb0\xd9', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.SONATA_HYBRID: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', + b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', + b'\xf1\x8799110L5000\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', + b'\xf1\x8799110L5000\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', + b'\xf1\x8756310-L5450\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', + b'\xf1\x8756310-L5450\xf1\x00DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', + b'\xf1\x8756310-L5500\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', + b'\xf1\x8756310L5450\x00\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00PSBG2323 E09\x00\x00\x00\x00\x00\x00\x00TDN2H20SA5\x97R\x88\x9e', + b'\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TDN2H20SA6N\xc2\xeeW', + b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDN2H20SA7\x1a3\xf9\xab', + b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E09\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2323 E09\x00\x00\x00\x00\x00\x00\x00TDN2H20SA5\x97R\x88\x9e', + b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TDN2H20SA6N\xc2\xeeW', + b'\xf1\x87PCU\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDN2H20SA7\x1a3\xf9\xab', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391062J002', + b'\xf1\x87391162J012', + b'\xf1\x87391162J013', + b'\xf1\x87391162J014', + ], + }, + CAR.KIA_SORENTO: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x87LDKUAA0348164HE3\x87www\x87www\x88\x88\xa8\x88w\x88\x97xw\x88\x97x\x86o\xf8\xff\x87f\x7f\xff\x15\xe0\xf1\x81U811\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U811\x00\x00\x00\x00\x00\x00TUM4G33NL3V|DG', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.KIA_EV6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', + b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', + ], + }, + CAR.IONIQ_5: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', + b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.00 99211-GI020 230719', + b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI020 230719', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', + ], + }, + CAR.IONIQ_6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', + b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', + ], + }, + CAR.TUCSON_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', + b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', + b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', + b'\xf1\x00NX4__ 1.00 1.02 99110-N9000 ', + b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', + ], + }, + CAR.SANTA_CRUZ_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', + b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', + ], + }, + CAR.KIA_SPORTAGE_5TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', + b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', + b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', + b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', + ], + }, + CAR.GENESIS_GV70_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', + ], + }, + CAR.GENESIS_GV60_EV_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', + b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', + b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', + ], + }, + CAR.KIA_SORENTO_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.00 99110-R5000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', + ], + }, + CAR.KIA_SORENTO_HEV_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', + b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', + b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.10 99210-P2000 210406', + b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', + b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', + b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', + ], + }, + CAR.KIA_NIRO_HEV_2ND_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', + b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + }, + CAR.GENESIS_GV80: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', + ], + }, + CAR.KIA_CARNIVAL_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KA4 MFC AT KOR LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.05 99210-R0000 201221', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', + b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', + ], + }, + CAR.KIA_K8_HEV_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', + ], + }, + CAR.STARIA_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00US4 MFC AT KOR LHD 1.00 1.06 99211-CG000 230524', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00US4_ RDR ----- 1.00 1.00 99110-CG000 ', + ], + }, +} diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 26b3491358..049a63399c 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -34,6 +34,12 @@ class CarInterface(CarInterfaceBase): CAN = CanBus(None, hda2, fingerprint) if candidate in CANFD_CAR: + # detect if car is hybrid + if 0x105 in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.HYBRID.value + elif candidate in EV_CAR: + ret.flags |= HyundaiFlags.EV.value + # detect HDA2 with ADAS Driving ECU if hda2: ret.flags |= HyundaiFlags.CANFD_HDA2.value @@ -52,6 +58,12 @@ class CarInterface(CarInterfaceBase): if candidate not in CANFD_RADAR_SCC_CAR: ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value else: + # TODO: detect EV and hybrid + if candidate in HYBRID_CAR: + ret.flags |= HyundaiFlags.HYBRID.value + elif candidate in EV_CAR: + ret.flags |= HyundaiFlags.EV.value + # Send LFA message on cars with HDA if 0x485 in fingerprint[2]: ret.flags |= HyundaiFlags.SEND_LFA.value @@ -136,7 +148,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.67 ret.steerRatio = 14.00 * 1.15 ret.tireStiffnessFactor = 0.385 - elif candidate in (CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN): + elif candidate == CAR.TUCSON_4TH_GEN: ret.mass = 1630. # average ret.wheelbase = 2.756 ret.steerRatio = 16. @@ -150,13 +162,17 @@ class CarInterface(CarInterfaceBase): ret.mass = 1690. # from https://www.hyundai-motor.com.tw/clicktobuy/custin#spec_0 ret.wheelbase = 3.055 ret.steerRatio = 17.0 # from learner + elif candidate == CAR.STARIA_4TH_GEN: + ret.mass = 2205. + ret.wheelbase = 3.273 + ret.steerRatio = 11.94 # https://www.hyundai.com/content/dam/hyundai/au/en/models/staria-load/premium-pip-update-2023/spec-sheet/STARIA_Load_Spec-Table_March_2023_v3.1.pdf # Kia elif candidate == CAR.KIA_SORENTO: ret.mass = 1985. ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable - elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_NIRO_HEV_2ND_GEN): + elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_NIRO_HEV_2ND_GEN, CAR.KIA_NIRO_PHEV_2022): ret.mass = 3543. * CV.LB_TO_KG # average of all the cars ret.wheelbase = 2.7 ret.steerRatio = 13.6 # average of all the cars @@ -168,7 +184,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.63 ret.steerRatio = 14.56 elif candidate == CAR.KIA_SPORTAGE_5TH_GEN: - ret.mass = 1700. # weight from SX and above trims, average of FWD and AWD versions + ret.mass = 1725. # weight from SX and above trims, average of FWD and AWD versions ret.wheelbase = 2.756 ret.steerRatio = 13.6 # steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications elif candidate in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL): @@ -202,19 +218,13 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.9 ret.steerRatio = 16. ret.tireStiffnessFactor = 0.65 - elif candidate == CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: - ret.mass = 1767. # SX Prestige trim support only - ret.wheelbase = 2.756 - ret.steerRatio = 13.6 - elif candidate in (CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN): + elif candidate in (CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN): ret.wheelbase = 2.81 ret.steerRatio = 13.5 # average of the platforms if candidate == CAR.KIA_SORENTO_4TH_GEN: ret.mass = 3957 * CV.LB_TO_KG - elif candidate == CAR.KIA_SORENTO_HEV_4TH_GEN: - ret.mass = 4255 * CV.LB_TO_KG else: - ret.mass = 4537 * CV.LB_TO_KG + ret.mass = 4396 * CV.LB_TO_KG elif candidate == CAR.KIA_CARNIVAL_4TH_GEN: ret.mass = 2087. ret.wheelbase = 3.09 @@ -260,8 +270,7 @@ class CarInterface(CarInterfaceBase): if candidate in CANFD_CAR: ret.longitudinalTuning.kpV = [0.1] ret.longitudinalTuning.kiV = [0.0] - ret.experimentalLongitudinalAvailable = (candidate in (HYBRID_CAR | EV_CAR) and candidate not in - (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR)) + ret.experimentalLongitudinalAvailable = candidate not in (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR) else: ret.longitudinalTuning.kpV = [0.5] ret.longitudinalTuning.kiV = [0.0] @@ -309,9 +318,9 @@ class CarInterface(CarInterfaceBase): if ret.openpilotLongitudinalControl: ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG - if candidate in HYBRID_CAR: + if ret.flags & HyundaiFlags.HYBRID: ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS - elif candidate in EV_CAR: + elif ret.flags & HyundaiFlags.EV: ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS if candidate in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV, CAR.KONA_EV_2022): diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 2d64d7a100..20fc29897d 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1,4 +1,3 @@ -# ruff: noqa: E501 import re from dataclasses import dataclass from enum import Enum, IntFlag, StrEnum @@ -65,6 +64,8 @@ class HyundaiFlags(IntFlag): SEND_LFA = 128 USE_FCA = 256 CANFD_HDA2_ALT_STEERING = 512 + HYBRID = 1024 + EV = 2048 class CAR(StrEnum): @@ -93,6 +94,7 @@ class CAR(StrEnum): SANTA_FE_PHEV_2022 = "HYUNDAI SANTA FE PlUG-IN HYBRID 2022" SONATA = "HYUNDAI SONATA 2020" SONATA_LF = "HYUNDAI SONATA 2019" + STARIA_4TH_GEN = "HYUNDAI STARIA 4TH GEN" TUCSON = "HYUNDAI TUCSON 2019" PALISADE = "HYUNDAI PALISADE 2020" VELOSTER = "HYUNDAI VELOSTER 2019" @@ -100,7 +102,6 @@ class CAR(StrEnum): IONIQ_5 = "HYUNDAI IONIQ 5 2022" IONIQ_6 = "HYUNDAI IONIQ 6 2023" TUCSON_4TH_GEN = "HYUNDAI TUCSON 4TH GEN" - TUCSON_HYBRID_4TH_GEN = "HYUNDAI TUCSON HYBRID 4TH GEN" SANTA_CRUZ_1ST_GEN = "HYUNDAI SANTA CRUZ 1ST GEN" CUSTIN_1ST_GEN = "HYUNDAI CUSTIN 1ST GEN" @@ -112,6 +113,7 @@ class CAR(StrEnum): KIA_NIRO_EV = "KIA NIRO EV 2020" KIA_NIRO_EV_2ND_GEN = "KIA NIRO EV 2ND GEN" KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019" + KIA_NIRO_PHEV_2022 = "KIA NIRO PLUG-IN HYBRID 2022" KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021" KIA_NIRO_HEV_2ND_GEN = "KIA NIRO HYBRID 2ND GEN" KIA_OPTIMA_G4 = "KIA OPTIMA 4TH GEN" @@ -123,8 +125,6 @@ class CAR(StrEnum): KIA_SORENTO = "KIA SORENTO GT LINE 2018" KIA_SORENTO_4TH_GEN = "KIA SORENTO 4TH GEN" KIA_SORENTO_HEV_4TH_GEN = "KIA SORENTO HYBRID 4TH GEN" - KIA_SORENTO_PHEV_4TH_GEN = "KIA SORENTO PLUG-IN HYBRID 4TH GEN" - KIA_SPORTAGE_HYBRID_5TH_GEN = "KIA SPORTAGE HYBRID 5TH GEN" KIA_STINGER = "KIA STINGER GT2 2018" KIA_STINGER_2022 = "KIA STINGER 2022" KIA_CEED = "KIA CEED INTRO ED 2019" @@ -159,7 +159,10 @@ class HyundaiCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.AZERA_6TH_GEN: HyundaiCarInfo("Hyundai Azera 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - CAR.AZERA_HEV_6TH_GEN: HyundaiCarInfo("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), + CAR.AZERA_HEV_6TH_GEN: [ + HyundaiCarInfo("Hyundai Azera Hybrid 2019", "All", car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarInfo("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), + ], CAR.ELANTRA: [ # TODO: 2017-18 could be Hyundai G HyundaiCarInfo("Hyundai Elantra 2017-18", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b])), @@ -186,18 +189,19 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KONA: HyundaiCarInfo("Hyundai Kona 2020", car_parts=CarParts.common([CarHarness.hyundai_b])), CAR.KONA_EV: HyundaiCarInfo("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g])), CAR.KONA_EV_2022: HyundaiCarInfo("Hyundai Kona Electric 2022-23", car_parts=CarParts.common([CarHarness.hyundai_o])), - CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", video_link="https://youtu.be/0dwpAHiZgFo", - car_parts=CarParts.common([CarHarness.hyundai_i])), # TODO: check packages + CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_i])), # TODO: check packages # TODO: this is the 2024 US MY, not yet released CAR.KONA_EV_2ND_GEN: HyundaiCarInfo("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", car_parts=CarParts.common([CarHarness.hyundai_r])), - CAR.SANTA_FE: HyundaiCarInfo("Hyundai Santa Fe 2019-20", "All", car_parts=CarParts.common([CarHarness.hyundai_d])), + CAR.SANTA_FE: HyundaiCarInfo("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", + car_parts=CarParts.common([CarHarness.hyundai_d])), CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", car_parts=CarParts.common([CarHarness.hyundai_l])), CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), CAR.SANTA_FE_PHEV_2022: HyundaiCarInfo("Hyundai Santa Fe Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", car_parts=CarParts.common([CarHarness.hyundai_a])), + CAR.STARIA_4TH_GEN: HyundaiCarInfo("Hyundai Staria 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), CAR.SONATA_LF: HyundaiCarInfo("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e])), CAR.TUCSON: [ HyundaiCarInfo("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_l])), @@ -220,8 +224,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.TUCSON_4TH_GEN: [ HyundaiCarInfo("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), HyundaiCarInfo("Hyundai Tucson 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarInfo("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), ], - CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), CAR.SANTA_CRUZ_1ST_GEN: HyundaiCarInfo("Hyundai Santa Cruz 2022-23", car_parts=CarParts.common([CarHarness.hyundai_n])), CAR.CUSTIN_1ST_GEN: HyundaiCarInfo("Hyundai Custin 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), @@ -244,8 +248,13 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), HyundaiCarInfo("Kia Niro Plug-in Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_d])), ], + CAR.KIA_NIRO_PHEV_2022: [ + HyundaiCarInfo("Kia Niro Plug-in Hybrid 2021", "All", car_parts=CarParts.common([CarHarness.hyundai_d])), + HyundaiCarInfo("Kia Niro Plug-in Hybrid 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_f])), + ], CAR.KIA_NIRO_HEV_2021: [ - HyundaiCarInfo("Kia Niro Hybrid 2021-22", car_parts=CarParts.common([CarHarness.hyundai_f])), # TODO: 2021 could be hyundai_d, verify + HyundaiCarInfo("Kia Niro Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), + HyundaiCarInfo("Kia Niro Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), ], CAR.KIA_NIRO_HEV_2ND_GEN: HyundaiCarInfo("Kia Niro Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_a])), CAR.KIA_OPTIMA_G4: HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", @@ -255,16 +264,20 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KIA_OPTIMA_H: HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control", car_parts=CarParts.common([CarHarness.hyundai_c])), CAR.KIA_OPTIMA_H_G4_FL: HyundaiCarInfo("Kia Optima Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_h])), CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", car_parts=CarParts.common([CarHarness.hyundai_a])), - CAR.KIA_SPORTAGE_5TH_GEN: HyundaiCarInfo("Kia Sportage 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), + CAR.KIA_SPORTAGE_5TH_GEN: [ + HyundaiCarInfo("Kia Sportage 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarInfo("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), + ], CAR.KIA_SORENTO: [ HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), ], CAR.KIA_SORENTO_4TH_GEN: HyundaiCarInfo("Kia Sorento 2021-23", car_parts=CarParts.common([CarHarness.hyundai_k])), - CAR.KIA_SORENTO_HEV_4TH_GEN: HyundaiCarInfo("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - CAR.KIA_SORENTO_PHEV_4TH_GEN: HyundaiCarInfo("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: HyundaiCarInfo("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), + CAR.KIA_SORENTO_HEV_4TH_GEN: [ + HyundaiCarInfo("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarInfo("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + ], CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", car_parts=CarParts.common([CarHarness.hyundai_c])), CAR.KIA_STINGER_2022: HyundaiCarInfo("Kia Stinger 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), @@ -275,7 +288,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia EV6 (with HDA II) 2022-23", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) ], CAR.KIA_CARNIVAL_4TH_GEN: [ - HyundaiCarInfo("Kia Carnival 2023-24", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarInfo("Kia Carnival 2022-24", car_parts=CarParts.common([CarHarness.hyundai_a])), HyundaiCarInfo("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) ], @@ -302,81 +315,6 @@ class Buttons: GAP_DIST = 3 CANCEL = 4 # on newer models, this is a pause/resume button -FINGERPRINTS = { - CAR.HYUNDAI_GENESIS: [{ - 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 - }, - { - 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1378: 4, 1379: 8, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 - }, - { - 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1268: 8, 1280: 1, 1281: 3, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1437: 8, 1456: 4 - }, - { - 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1378: 4, 1379: 8, 1384: 5, 1407: 8, 1425: 2, 1427: 6, 1437: 8, 1456: 4 - }, - { - 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1437: 8, 1456: 4 - }], - CAR.SANTA_FE: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8 - }, - { - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 764: 8, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1186: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 - }, - { - 67: 8, 68: 8, 80: 4, 160: 8, 161: 8, 272: 8, 288: 4, 339: 8, 356: 8, 357: 8, 399: 8, 544: 8, 608: 8, 672: 8, 688: 5, 704: 1, 790: 8, 809: 8, 848: 8, 880: 8, 898: 8, 900: 8, 901: 8, 904: 8, 1056: 8, 1064: 8, 1065: 8, 1072: 8, 1075: 8, 1087: 8, 1088: 8, 1151: 8, 1200: 8, 1201: 8, 1232: 4, 1264: 8, 1265: 8, 1266: 8, 1296: 8, 1306: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1348: 8, 1349: 8, 1369: 8, 1370: 8, 1371: 8, 1407: 8, 1415: 8, 1419: 8, 1440: 8, 1442: 4, 1461: 8, 1470: 8 - }], - CAR.SONATA: [ - {67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 549: 8, 550: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1096: 8, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1379: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8}, - ], - CAR.SONATA_LF: [ - {66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1397: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2014: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8}, - ], - CAR.KIA_SORENTO: [{ - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 - }], - CAR.KIA_STINGER: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 - }], - CAR.GENESIS_G80: [{ - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1024: 2, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8 - }, - { - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 546: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1437: 8, 1456: 4, 1470: 8 - }, - { - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1162: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1193: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1437: 8, 1456: 4, 1470: 8 - }], - CAR.GENESIS_G90: [{ - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 - }], - CAR.IONIQ_EV_2020: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 7, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 - }], - CAR.IONIQ: [{ - 68:8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1473: 8, 1476: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8 - }], - CAR.KONA_EV: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 1157: 4, 1193: 8, 1379: 8, 1988: 8, 1996: 8 - }], - CAR.KONA_EV_2022: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1069: 8, 1078: 4, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1173: 8, 1183: 8, 1188: 8, 1191: 2, 1193: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1339: 8, 1342: 8, 1343: 8, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1446: 8, 1456: 4, 1470: 8, 1473: 8, 1485: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8 - }], - CAR.KIA_NIRO_EV: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 - }], - CAR.KIA_OPTIMA_H: [{ - 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1236: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 - }, - { - 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1420: 8, 1425: 2, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 - }], - CAR.PALISADE: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 547: 8, 548: 8, 549: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1123: 8, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8 - }], -} - def get_platform_codes(fw_versions: List[bytes]) -> Set[Tuple[bytes, Optional[bytes]]]: # Returns unique, platform-specific identification codes for a set of versions @@ -397,15 +335,14 @@ def get_platform_codes(fw_versions: List[bytes]) -> Set[Tuple[bytes, Optional[by return codes -def match_fw_to_car_fuzzy(live_fw_versions) -> Set[str]: +def match_fw_to_car_fuzzy(live_fw_versions, offline_fw_versions) -> Set[str]: # Non-electric CAN FD platforms often do not have platform code specifiers needed # to distinguish between hybrid and ICE. All EVs so far are either exclusively # electric or specify electric in the platform code. - # TODO: whitelist platforms that we've seen hybrid and ICE versions of that have these specifiers - fuzzy_platform_blacklist = {str(c) for c in set(CANFD_CAR - EV_CAR)} + fuzzy_platform_blacklist = {str(c) for c in (CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST)} candidates: Set[str] = set() - for candidate, fws in FW_VERSIONS.items(): + for candidate, fws in offline_fw_versions.items(): # Keep track of ECUs which pass all checks (platform codes, within date range) valid_found_ecus = set() valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} @@ -459,6 +396,9 @@ HYUNDAI_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER] p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_SOFTWARE_IDENTIFICATION) + \ p16(0xf100) +HYUNDAI_ECU_MANUFACTURING_DATE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.ECU_MANUFACTURING_DATE) + HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) # Regex patterns for parsing platform code, FW date, and part number from FW versions @@ -467,6 +407,9 @@ PLATFORM_CODE_FW_PATTERN = re.compile(b'((?<=' + HYUNDAI_VERSION_REQUEST_LONG[1: DATE_FW_PATTERN = re.compile(b'(?<=[ -])([0-9]{6}$)') PART_NUMBER_FW_PATTERN = re.compile(b'(?<=[0-9][.,][0-9]{2} )([0-9]{5}[-/]?[A-Z][A-Z0-9]{3}[0-9])') +# We've seen both ICE and hybrid for these platforms, and they have hybrid descriptors (e.g. MQ4 vs MQ4H) +CANFD_FUZZY_WHITELIST = {CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN} + # List of ECUs expected to have platform codes, camera and radar should exist on all cars # TODO: use abs, it has the platform code and part number on many platforms PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] @@ -474,6 +417,8 @@ PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] # TODO: there are date codes in the ABS firmware versions in hex DATE_FW_ECUS = [Ecu.fwdCamera] +ALL_HYUNDAI_ECUS = [Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.engine, Ecu.parkingAdas, Ecu.transmission, Ecu.adas, Ecu.hvac, Ecu.cornerRadar] + FW_QUERY_CONFIG = FwQueryConfig( requests=[ # TODO: minimize shared whitelists for CAN and cornerRadar for CAN-FD @@ -507,13 +452,52 @@ FW_QUERY_CONFIG = FwQueryConfig( obd_multiplexing=False, ), - # CAN-FD debugging queries + # CAN & CAN FD query to understand the three digit date code + # HDA2 cars usually use 6 digit date codes, so skip bus 1 + Request( + [HYUNDAI_ECU_MANUFACTURING_DATE], + [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + auxiliary=True, + logging=True, + ), + + # CAN & CAN FD logging queries (from camera) + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=ALL_HYUNDAI_ECUS, + bus=0, + auxiliary=True, + logging=True, + ), + Request( + [HYUNDAI_VERSION_REQUEST_MULTI], + [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=ALL_HYUNDAI_ECUS, + bus=0, + auxiliary=True, + logging=True, + ), + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + whitelist_ecus=ALL_HYUNDAI_ECUS, + bus=1, + auxiliary=True, + obd_multiplexing=False, + logging=True, + ), + + # CAN-FD alt request logging queries Request( [HYUNDAI_VERSION_REQUEST_ALT], [HYUNDAI_VERSION_RESPONSE], whitelist_ecus=[Ecu.parkingAdas, Ecu.hvac], bus=0, auxiliary=True, + logging=True, ), Request( [HYUNDAI_VERSION_REQUEST_ALT], @@ -521,6 +505,7 @@ FW_QUERY_CONFIG = FwQueryConfig( whitelist_ecus=[Ecu.parkingAdas, Ecu.hvac], bus=1, auxiliary=True, + logging=True, obd_multiplexing=False, ), ], @@ -534,1566 +519,6 @@ FW_QUERY_CONFIG = FwQueryConfig( match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, ) -FW_VERSIONS = { - CAR.AZERA_6TH_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 U912\x00\x00\x00\x00\x00\x00SIG0M35MH0\xa4 |.', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81641KA051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.AZERA_HEV_6TH_GEN: { - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x006T7N0_C2\x00\x006T7VA051\x00\x00TIGSH24KA1\xc7\x85\xe2`', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H590051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.HYUNDAI_GENESIS: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS 1.1 -150210', - b'\xf1\x00DH LKAS 1.4 -140110', - b'\xf1\x00DH LKAS 1.5 -140425', - ], - }, - CAR.IONIQ: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6F2051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U3H1051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H1051\x00\x00HAE0G16US2\x00\x00\x00\x00', - ], - }, - CAR.IONIQ_PHEV_2019: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PAE0G16NS1\xdbD\r\x81', - b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PAE0G16NS1\x00\x00\x00\x00', - ], - }, - CAR.IONIQ_PHEV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U3J9051\000\000\xf1\0006U3H1_C2\000\0006U3J9051\000\000PAE0G16NL0\x82zT\xd2', - b'\xf1\x816U3J8051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J8051\x00\x00PAETG16UL0\x00\x00\x00\x00', - b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\x00\x00\x00\x00', - b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL0\x00\x00\x00\x00', - b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\xad\xeb\xabt', - b'\xf1\x006U3H1_C2\x00\x006U3J8051\x00\x00PAETG16UL0\x00\x00\x00\x00', - ], - }, - CAR.IONIQ_EV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', - b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', - ], - }, - CAR.IONIQ_EV_LTD: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', - b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.IONIQ_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HAE0G16NL2\x00\x00\x00\x00', - b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HAE0G16NL2\x96\xda\xd4\xee', - ], - }, - CAR.SONATA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', - b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', - b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', - b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', - b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', - b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', - b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', - b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81HM6M1_0a0_F00', - b'\xf1\x82DNBVN5GMCCXXXDCA', - b'\xf1\x82DNBVN5GMCCXXXG2F', - b'\xf1\x82DNBWN5TMDCXXXG2E', - b'\xf1\x82DNCVN5GMCCXXXF0A', - b'\xf1\x82DNCVN5GMCCXXXG2B', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_J10', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82DNDWN5TMDCXXXJ1A', - b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M10', - b'\xf1\x87391162M003', - b'\xf1\x87391162M013', - b'\xf1\x87391162M023', - b'\xf1\x87391162M010', - b'HM6M1_0a0_F00', - b'HM6M1_0a0_G20', - b'HM6M2_0a0_BD0', - b'\xf1\x8739110-2S278\xf1\x82DNDVD5GMCCXXXL5B', - b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M00', - b'\xf1\x8739110-2S042\xf1\x81HM6M1_0a0_M00', - b'\xf1\x81HM6M1_0a0_G20', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', # modified firmware - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', - b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', # modified firmware - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', - b'\xf1\x8756310-L0010\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', - b'\xf1\x8756310-L0210\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', - b'\xf1\x8756310-L1010\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', - b'\xf1\x8756310-L1030\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', - b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', - b'\xf1\x8756310L0210\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', - b'\xf1\x8757700-L0000\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', - b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', - b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16KB05\x95h%', - b'\xf1\x00HT6TA260BLHT6TA800A1TDN8C20KS4\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x00HT6TA260BLHT6TA810A1TDN8M25GS0\x00\x00\x00\x00\x00\x00\xaa\x8c\xd9p', - b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x96\xa1\xf1\x92', - b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB2\x00\x00\x00\x00\x00\x00\x08\xc9O:', - b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB4\x00\x00\x00\x00\x00\x00g!l[', - b'\xf1\x00HT6WA280BLHT6WAE10A1SDN8G25NB5\x00\x00\x00\x00\x00\x00\xe0t\xa9\xba', - b'\xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', - b'\xf1\x00T02601BL T02832A1 VDN8T25XXX832NS8G\x0e\xfeE', - b'\xf1\x00T02601BL T02900A1 VDN8T25XXX900NSCF\xe4!Y', - b'\xf1\x87954A02N060\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', - b'\xf1\x87SAKFBA2926554GJ2VefVww\x87xwwwww\x88\x87xww\x87wTo\xfb\xffvUo\xff\x8d\x16\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SAKFBA3030524GJ2UVugww\x97yx\x88\x87\x88vw\x87gww\x87wto\xf9\xfffUo\xff\xa2\x0c\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SAKFBA3356084GJ2\x86fvgUUuWgw\x86www\x87wffvf\xb6\xcf\xfc\xffeUO\xff\x12\x19\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SAKFBA3474944GJ2ffvgwwwwg\x88\x86x\x88\x88\x98\x88ffvfeo\xfa\xff\x86fo\xff\t\xae\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SAKFBA3475714GJ2Vfvgvg\x96yx\x88\x97\x88ww\x87ww\x88\x87xs_\xfb\xffvUO\xff\x0f\xff\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALDBA3510954GJ3ww\x87xUUuWx\x88\x87\x88\x87w\x88wvfwfc_\xf9\xff\x98wO\xffl\xe0\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA3573534GJ3\x89\x98\x89\x88EUuWgwvwwwwww\x88\x87xTo\xfa\xff\x86f\x7f\xffo\x0e\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA3601464GJ3\x88\x88\x88\x88ffvggwvwvw\x87gww\x87wvo\xfb\xff\x98\x88\x7f\xffjJ\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA3753044GJ3UUeVff\x86hwwwwvwwgvfgfvo\xf9\xfffU_\xffC\xae\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA3862294GJ3vfvgvefVxw\x87\x87w\x88\x87xwwwwc_\xf9\xff\x87w\x9f\xff\xd5\xdc\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA3873834GJ3fefVwuwWx\x88\x97\x88w\x88\x97xww\x87wU_\xfb\xff\x86f\x8f\xffN\x04\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA4525334GJ3\x89\x99\x99\x99fevWh\x88\x86\x88fwvgw\x88\x87xfo\xfa\xffuDo\xff\xd1>\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA4626804GJ3wwww\x88\x87\x88xx\x88\x87\x88wwgw\x88\x88\x98\x88\x95_\xf9\xffuDo\xff|\xe7\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA4803224GJ3wwwwwvwg\x88\x88\x98\x88wwww\x87\x88\x88xu\x9f\xfc\xff\x87f\x8f\xff\xea\xea\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA6212564GJ3\x87wwwUTuGg\x88\x86xx\x88\x87\x88\x87\x88\x98xu?\xf9\xff\x97f\x7f\xff\xb8\n\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA6347404GJ3wwwwff\x86hx\x88\x97\x88\x88\x88\x88\x88vfgf\x88?\xfc\xff\x86Uo\xff\xec/\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA6901634GJ3UUuWVeVUww\x87wwwwwvUge\x86/\xfb\xff\xbb\x99\x7f\xff]2\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALDBA7077724GJ3\x98\x88\x88\x88ww\x97ygwvwww\x87ww\x88\x87x\x87_\xfd\xff\xba\x99o\xff\x99\x01\xf1\x89HT6WA910A1\xf1\x82SDN8G25NB1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALFBA3525114GJ2wvwgvfvggw\x86wffvffw\x86g\x85_\xf9\xff\xa8wo\xffv\xcd\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA3624024GJ2\x88\x88\x88\x88wv\x87hx\x88\x97\x88x\x88\x97\x88ww\x87w\x86o\xfa\xffvU\x7f\xff\xd1\xec\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA3960824GJ2wwwwff\x86hffvfffffvfwfg_\xf9\xff\xa9\x88\x8f\xffb\x99\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA4011074GJ2fgvwwv\x87hw\x88\x87xww\x87wwfgvu_\xfa\xffefo\xff\x87\xc0\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA4121304GJ2x\x87xwff\x86hwwwwww\x87wwwww\x84_\xfc\xff\x98\x88\x9f\xffi\xa6\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA4195874GJ2EVugvf\x86hgwvwww\x87wgw\x86wc_\xfb\xff\x98\x88\x8f\xff\xe23\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA4625294GJ2eVefeUeVx\x88\x97\x88wwwwwwww\xa7o\xfb\xffvw\x9f\xff\xee.\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA4728774GJ2vfvg\x87vwgww\x87ww\x88\x97xww\x87w\x86_\xfb\xffeD?\xffk0\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA5129064GJ2vfvgwv\x87hx\x88\x87\x88ww\x87www\x87wd_\xfa\xffvfo\xff\x1d\x00\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA5454914GJ2\x98\x88\x88\x88\x87vwgx\x88\x87\x88xww\x87ffvf\xa7\x7f\xf9\xff\xa8w\x7f\xff\x1b\x90\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA5987784GJ2UVugDDtGx\x88\x87\x88w\x88\x87xwwwwd/\xfb\xff\x97fO\xff\xb0h\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA5987864GJ2fgvwUUuWgwvw\x87wxwwwww\x84/\xfc\xff\x97w\x7f\xff\xdf\x1d\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA6337644GJ2vgvwwv\x87hgffvwwwwwwww\x85O\xfa\xff\xa7w\x7f\xff\xc5\xfc\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA6802004GJ2UUuWUUuWgw\x86www\x87www\x87w\x96?\xf9\xff\xa9\x88\x7f\xff\x9fK\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA6892284GJ233S5\x87w\x87xx\x88\x87\x88vwwgww\x87w\x84?\xfb\xff\x98\x88\x8f\xff*\x9e\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', - b'\xf1\x87SALFBA7005534GJ2eUuWfg\x86xxww\x87x\x88\x87\x88\x88w\x88\x87\x87O\xfc\xffuUO\xff\xa3k\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', - b'\xf1\x87SALFBA7152454GJ2gvwgFf\x86hx\x88\x87\x88vfWfffffd?\xfa\xff\xba\x88o\xff,\xcf\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', - b'\xf1\x87SALFBA7485034GJ2ww\x87xww\x87xfwvgwwwwvfgf\xa5/\xfc\xff\xa9w_\xff40\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SAMDBA7743924GJ3wwwwww\x87xgwvw\x88\x88\x88\x88wwww\x85_\xfa\xff\x86f\x7f\xff0\x9d\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB2\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SAMDBA7817334GJ3Vgvwvfvgww\x87wwwwwwfgv\x97O\xfd\xff\x88\x88o\xff\x8e\xeb\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB2\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SAMDBA8054504GJ3gw\x87xffvgffffwwwweUVUf?\xfc\xffvU_\xff\xddl\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB2\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SAMFB41553621GC7ww\x87xUU\x85Xvwwg\x88\x88\x88\x88wwgw\x86\xaf\xfb\xffuDo\xff\xaa\x8f\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SAMFB42555421GC7\x88\x88\x88\x88wvwgx\x88\x87\x88wwgw\x87wxw3\x8f\xfc\xff\x98f\x8f\xffga\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SAMFBA7978674GJ2gw\x87xgw\x97ywwwwvUGeUUeU\x87O\xfb\xff\x98w\x8f\xfffF\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SAMFBA9283024GJ2wwwwEUuWwwgwwwwwwwww\x87/\xfb\xff\x98w\x8f\xff<\xd3\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SAMFBA9708354GJ2wwwwVf\x86h\x88wx\x87xww\x87\x88\x88\x88\x88w/\xfa\xff\x97w\x8f\xff\x86\xa0\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SANDB45316691GC6\x99\x99\x99\x99\x88\x88\xa8\x8avfwfwwww\x87wxwT\x9f\xfd\xff\x88wo\xff\x1c\xfa\xf1\x89HT6WAD10A1\xf1\x82SDN8G25NB3\x00\x00\x00\x00\x00\x00', - b'\xf1\x87SALFBA7460044GJ2gx\x87\x88Vf\x86hx\x88\x87\x88wwwwgw\x86wd?\xfa\xff\x86U_\xff\xaf\x1f\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SAMFBA8105254GJ2wx\x87\x88Vf\x86hx\x88\x87\x88wwwwwwww\x86O\xfa\xff\x99\x88\x7f\xffZG\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x87SANFB45889451GC7wx\x87\x88gw\x87x\x88\x88x\x88\x87wxw\x87wxw\x87\x8f\xfc\xffeU\x8f\xff+Q\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', - b'\xf1\x00T02601BL T02900A1 VDN8T25XXX900NSA\xb9\x13\xf9p', - ], - }, - CAR.SONATA_LF: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LF ESC \f 11 \x17\x01\x13 58920-C2610', - b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81606D5051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81606D5K51\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81606G1051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', - b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5', - b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\x00\x00\x00\x00', - b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5', - b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24SL2n\x8d\xbe\xd8', - b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2\x00\x00\x00\x00', - b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm', - b'\xf1\x87LAJSG49645724HF0\x87x\x87\x88\x87www\x88\x99\xa8\x89\x88\x99\xa8\x89\x88\x99\xa8\x89S_\xfb\xff\x87f\x7f\xff^2\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm', - ], - }, - CAR.TUCSON: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', - b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8971TLC2NAIDDIR002\xf1\x8271TLC2NAIDDIR002', - b'\xf1\x81606G3051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', - b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87LBJXAN202299KF22\x87x\x87\x88ww\x87xx\x88\x97\x88\x87\x88\x98x\x88\x99\x98\x89\x87o\xf6\xff\x87w\x7f\xff\x12\x9a\xf1\x81U083\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U083\x00\x00\x00\x00\x00\x00TTL2V20KL1\x8fRn\x8a', - b'\xf1\x87KMLDCU585233TJ20wx\x87\x88x\x88\x98\x89vfwfwwww\x87f\x9f\xff\x98\xff\x7f\xf9\xf7s\xf1\x816T6G4051\x00\x00\xf1\x006T6J0_C2\x00\x006T6G4051\x00\x00TTL4G24NH2\x00\x00\x00\x00', - ], - }, - CAR.SANTA_FE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', - b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', - b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', - b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', - b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', - b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', - b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81606EA051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81606G1051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81606G3051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', - b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', - b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', - b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 U833\x00\x00\x00\x00\x00\x00TTM4V22US3_<]\xf1', - b'\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00', - b'\xf1\x87LBJSGA7082574HG0\x87www\x98\x88\x88\x88\x99\xaa\xb9\x9afw\x86gx\x99\xa7\x89co\xf8\xffvU_\xffR\xaf\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2T20NS1\x00\xa6\xe0\x91', - b'\xf1\x87LBKSGA0458404HG0vfvg\x87www\x89\x99\xa8\x99y\xaa\xa7\x9ax\x88\xa7\x88t_\xf9\xff\x86w\x8f\xff\x15x\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2T20NS1\x00\x00\x00\x00', - b'\xf1\x87LDJUEA6010814HG1\x87w\x87x\x86gvw\x88\x88\x98\x88gw\x86wx\x88\x97\x88\x85o\xf8\xff\x86f_\xff\xd37\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS0\xf8\x19\x92g', - b'\xf1\x87LDJUEA6458264HG1ww\x87x\x97x\x87\x88\x88\x99\x98\x89g\x88\x86xw\x88\x97x\x86o\xf7\xffvw\x8f\xff3\x9a\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS0\xf8\x19\x92g', - b'\xf1\x87LDKUEA2045844HG1wwww\x98\x88x\x87\x88\x88\xa8\x88x\x99\x97\x89x\x88\xa7\x88U\x7f\xf8\xffvfO\xffC\x1e\xf1\x816W3E0051\x00\x00\xf1\x006W351_C2\x00\x006W3E0051\x00\x00TTM4T20NS3\x00\x00\x00\x00', - b'\xf1\x87LDKUEA9993304HG1\x87www\x97x\x87\x88\x99\x99\xa9\x99x\x99\xa7\x89w\x88\x97x\x86_\xf7\xffwwO\xffl#\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS1R\x7f\x90\n', - b'\xf1\x87LDLUEA6061564HG1\xa9\x99\x89\x98\x87wwwx\x88\x97\x88x\x99\xa7\x89x\x99\xa7\x89sO\xf9\xffvU_\xff<\xde\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS50\xcb\xc3\xed', - b'\xf1\x87LDLUEA6159884HG1\x88\x87hv\x99\x99y\x97\x89\xaa\xb8\x9ax\x99\x87\x89y\x99\xb7\x99\xa7?\xf7\xff\x97wo\xff\xf3\x05\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00', - b'\xf1\x87LDLUEA6852664HG1\x97wWu\x97www\x89\xaa\xc8\x9ax\x99\x97\x89x\x99\xa7\x89SO\xf7\xff\xa8\x88\x7f\xff\x03z\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS50\xcb\xc3\xed', - b'\xf1\x87LDLUEA6898374HG1fevW\x87wwwx\x88\x97\x88h\x88\x96\x88x\x88\xa7\x88ao\xf9\xff\x98\x99\x7f\xffD\xe2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00', - b'\xf1\x87LDLUEA6898374HG1fevW\x87wwwx\x88\x97\x88h\x88\x96\x88x\x88\xa7\x88ao\xf9\xff\x98\x99\x7f\xffD\xe2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS50\xcb\xc3\xed', - b'\xf1\x87SBJWAA5842214GG0\x88\x87\x88xww\x87x\x89\x99\xa8\x99\x88\x99\x98\x89w\x88\x87xw_\xfa\xfffU_\xff\xd1\x8d\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x98{|\xe3', - b'\xf1\x87SBJWAA5890864GG0\xa9\x99\x89\x98\x98\x87\x98y\x89\x99\xa8\x99w\x88\x87xww\x87wvo\xfb\xffuD_\xff\x9f\xb5\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x98{|\xe3', - b'\xf1\x87SBJWAA6562474GG0ffvgeTeFx\x88\x97\x88ww\x87www\x87w\x84o\xfa\xff\x87fO\xff\xc2 \xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x00\x00\x00\x00', - b'\xf1\x87SBJWAA6562474GG0ffvgeTeFx\x88\x97\x88ww\x87www\x87w\x84o\xfa\xff\x87fO\xff\xc2 \xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS1\x98{|\xe3', - b'\xf1\x87SBJWAA7780564GG0wvwgUUeVwwwwx\x88\x87\x88wwwwd_\xfc\xff\x86f\x7f\xff\xd7*\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS2F\x84<\xc0', - b'\xf1\x87SBJWAA8278284GG0ffvgUU\x85Xx\x88\x87\x88x\x88w\x88ww\x87w\x96o\xfd\xff\xa7U_\xff\xf2\xa0\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2G24NS2F\x84<\xc0', - b'\xf1\x87SBLWAA4363244GG0wvwgwv\x87hgw\x86ww\x88\x87xww\x87wdo\xfb\xff\x86f\x7f\xff3$\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS6\x00\x00\x00\x00', - b'\xf1\x87SBLWAA4363244GG0wvwgwv\x87hgw\x86ww\x88\x87xww\x87wdo\xfb\xff\x86f\x7f\xff3$\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS6x0\x17\xfe', - b'\xf1\x87SBLWAA4899564GG0VfvgUU\x85Xx\x88\x87\x88vfgf\x87wxwvO\xfb\xff\x97f\xb1\xffSB\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS7\x00\x00\x00\x00', - b'\xf1\x87SBLWAA6622844GG0wwwwff\x86hwwwwx\x88\x87\x88\x88\x88\x88\x88\x98?\xfd\xff\xa9\x88\x7f\xffn\xe5\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM2G24NS7u\x1e{\x1c', - b'\xf1\x87SDJXAA7656854GG1DEtWUU\x85X\x88\x88\x98\x88w\x88\x87xx\x88\x87\x88\x96o\xfb\xff\x86f\x7f\xff.\xca\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4G24NS2\x00\x00\x00\x00', - b'\xf1\x87SDJXAA7656854GG1DEtWUU\x85X\x88\x88\x98\x88w\x88\x87xx\x88\x87\x88\x96o\xfb\xff\x86f\x7f\xff.\xca\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4G24NS2K\xdaV0', - b'\xf1\x87SDKXAA2443414GG1vfvgwv\x87h\x88\x88\x88\x88ww\x87wwwww\x99_\xfc\xffvD?\xffl\xd2\xf1\x816W3E1051\x00\x00\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4G24NS6\x00\x00\x00\x00', - ], - }, - CAR.SANTA_FE_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', - b'\xf1\x8758910-S2DA0\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', - b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', - b'\xf1\x8758910-S1DA0\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', - b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', - b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', - b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_L50', - b'\xf1\x81HM6M1_0a0_H00', - b'\xf1\x82TACVN5GMI3XXXH0A', - b'\xf1\x82TMBZN5TMD3XXXG2E', - b'\xf1\x82TACVN5GSI3XXXH0A', - b'\xf1\x82TMCFD5MMCXXXXG0A', - b'\xf1\x81HM6M1_0a0_G20', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82TMDWN5TMD3TXXJ1A', - b'\xf1\x81HM6M2_0a0_G00', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_J10', - b'\xf1\x8739101-2STN8\xf1\x81HM6M1_0a0_M00', - b'\xf1\x87 \xf1\x81 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00HT6WA280BLHT6WAD00A1STM2G25NH2\x00\x00\x00\x00\x00\x00\xf8\xc0\xc3\xaa', - b'\xf1\x00HT6WA280BLHT6WAD00A1STM4G25NH1\x00\x00\x00\x00\x00\x00\x9cl\x04\xbc', - b'\xf1\x00T02601BL T02900A1 VTMPT25XXX900NSA\xf3\xf4Uj', - b'\xf1\x87SDMXCA9087684GN1VfvgUUeVwwgwwwwwffffU?\xfb\xff\x97\x88\x7f\xff+\xa4\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00', - b'\xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7', - b'\xf1\x87SDMXCA8653204GN1EVugEUuWwwwwww\x87wwwwwv/\xfb\xff\xa8\x88\x9f\xff\xa5\x9c\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7', - b'\xf1\x87KMMYBU034207SB72x\x89\x88\x98h\x88\x98\x89\x87fhvvfWf33_\xff\x87\xff\x8f\xfa\x81\xe5\xf1\x89HT6TAF00A1\xf1\x82STM0M25GS1\x00\x00\x00\x00\x00\x00', - b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6', - b'\xf1\x00HT6TA290BLHT6TAF00A1STM0M25GS1\x00\x00\x00\x00\x00\x006\xd8\x97\x15', - b'\xf1\x00T02601BL T02900A1 VTMPT25XXX900NS8\xb7\xaa\xfe\xfc', - b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02900A1 \xf1\x00T02601BL T02900A1 VTMPT25XXX900NS8\xb7\xaa\xfe\xfc', - b'\xf1\x00T02601BL T02800A1 VTMPT25XXX800NS4\xed\xaf\xed\xf5', - b'\xf1\x00T02601BL T02900A1 VTMPT25XXW900NS1c\x918\xc5', - ], - }, - CAR.SANTA_FE_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2H16SA3\xa3\x1b\xe14', - b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2H16UA3I\x94\xac\x8f', - b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TTM2H16SA2\x80\xd7l\xb2', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x87391312MTC1', - b'\xf1\x87391312MTE0', - b'\xf1\x87391312MTL0', - ], - }, - CAR.SANTA_FE_PHEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x8799110CL500\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8795441-3D121\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA0o\x88^\xbe', - b'\xf1\x8795441-3D121\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA1\x0b\xc5\x0f\xea', - b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA1\x0b\xc5\x0f\xea', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x87391312MTF0', - b'\xf1\x87391312MTF1', - ], - }, - CAR.CUSTIN_1ST_GEN: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x87391212MEC0', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 U928\x00\x00\x00\x00\x00\x00SKU0T15KB2\x92U\xf9M', - ], - }, - CAR.KIA_STINGER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81606DE051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81640E0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x82CKJN3TMSDE0B\x00\x00\x00\x00', - b'\xf1\x82CKKN3TMD_H0A\x00\x00\x00\x00', - b'\xe0\x19\xff\xe7\xe7g\x01\xa2\x00\x0f\x00\x9e\x00\x06\x00\xff\xff\xff\xff\xff\xff\x00\x00\xff\xff\xff\xff\xff\xff\x00\x00\x0f\x0e\x0f\x0f\x0e\r\x00\x00\x7f\x02.\xff\x00\x00~p\x00\x00\x00\x00u\xff\xf9\xff\x00\x00\x00\x00V\t\xd5\x01\xc0\x00\x00\x00\x007\xfb\xfc\x0b\x8d\x00', - b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', - b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', - b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SCK0T33NB2\xb3\xee\xba\xdc', - b'\xf1\x87VCJLE17622572DK0vd6D\x99\x98y\x97vwVffUfvfC%CuT&Dx\x87o\xff{\x1c\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', - b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', - b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x89E21\x00\x00\x00\x00\x00\x00\x00\xf1\x82SCK0T33NB0', - b'\xf1\x87VDHLG17034412DK2vD6DfVvVTD$D\x99w\x88\x98EDEDeT6DgfO\xff\xc3=\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', - b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', - b'\xf1\x87VDKLJ18675252DK6\x89vhgwwwwveVU\x88w\x87w\x99vgf\x97vXfgw_\xff\xc2\xfb\xf1\x89E25\x00\x00\x00\x00\x00\x00\x00\xf1\x82TCK0T33NB2', - b'\xf1\x87WAJTE17552812CH4vfFffvfVeT5DwvvVVdFeegeg\x88\x88o\xff\x1a]\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00TCK2T20NB1\x19\xd2\x00\x94', - b'\xf1\x87VDHLG17274082DK2wfFf\x89x\x98wUT5T\x88v\x97xgeGefTGTVvO\xff\x1c\x14\xf1\x81E19\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E19\x00\x00\x00\x00\x00\x00\x00SCK0T33UB2\xee[\x97S', - b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\t\xb7\x17\xf5', - b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\t\xb7\x17\xf5', - b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', - ], - }, - CAR.KIA_STINGER_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81640R0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81640N2051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81HM6M1_0a0_H00', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', - b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87VCNLF11383972DK1vffV\x99\x99\x89\x98\x86eUU\x88wg\x89vfff\x97fff\x99\x87o\xff"\xc1\xf1\x81E30\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E30\x00\x00\x00\x00\x00\x00\x00SCK0T33GH0\xbe`\xfb\xc6', - b'\xf1\x00bcsh8p54 E31\x00\x00\x00\x00\x00\x00\x00SCK0T33NH07\xdf\xf0\xc1', - b'\xf1\x00bcsh8p54 E31\x00\x00\x00\x00\x00\x00\x00SCK0T25KH2B\xfbI\xe2', - ], - }, - CAR.PALISADE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', - b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', - b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', - b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', - b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', - b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', - b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81640K0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81640S1051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', - b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', - b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', - b'\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', - b'\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00TON2G38NB5j\x94.\xde', - b'\xf1\x87LBLUFN591307KF25vgvw\x97wwwy\x99\xa7\x99\x99\xaa\xa9\x9af\x88\x96h\x95o\xf7\xff\x99f/\xff\xe4c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB2\xd7\xc1/\xd1', - b'\xf1\x87LBLUFN650868KF36\xa9\x98\x89\x88\xa8\x88\x88\x88h\x99\xa6\x89fw\x86gw\x88\x97x\xaa\x7f\xf6\xff\xbb\xbb\x8f\xff+\x82\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', - b'\xf1\x87LBLUFN655162KF36\x98\x88\x88\x88\x98\x88\x88\x88x\x99\xa7\x89x\x99\xa7\x89x\x99\x97\x89g\x7f\xf7\xffwU_\xff\xe9!\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', - b'\xf1\x87LBLUFN731381KF36\xb9\x99\x89\x98\x98\x88\x88\x88\x89\x99\xa8\x99\x88\x99\xa8\x89\x88\x88\x98\x88V\x7f\xf6\xff\x99w\x8f\xff\xad\xd8\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8', - b'\xf1\x87LDKVAA0028604HH1\xa8\x88x\x87vgvw\x88\x99\xa8\x89gw\x86ww\x88\x97x\x97o\xf9\xff\x97w\x7f\xffo\x02\xf1\x81U872\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', - b'\xf1\x87LDKVAA3068374HH1wwww\x87xw\x87y\x99\xa7\x99w\x88\x87xw\x88\x97x\x85\xaf\xfa\xffvU/\xffU\xdc\xf1\x81U872\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U872\x00\x00\x00\x00\x00\x00TON4G38NB1\x96z28', - b'\xf1\x87LDKVBN382172KF26\x98\x88\x88\x88\xa8\x88\x88\x88x\x99\xa7\x89\x87\x88\x98x\x98\x99\xa9\x89\xa5_\xf6\xffDDO\xff\xcd\x16\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', - b'\xf1\x87LDKVBN424201KF26\xba\xaa\x9a\xa9\x99\x99\x89\x98\x89\x99\xa8\x99\x88\x99\x98\x89\x88\x99\xa8\x89v\x7f\xf7\xffwf_\xffq\xa6\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', - b'\xf1\x87LDKVBN540766KF37\x87wgv\x87w\x87xx\x99\x97\x89v\x88\x97h\x88\x88\x88\x88x\x7f\xf6\xffvUo\xff\xd3\x01\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', - b'\xf1\x87LDLVAA4225634HH1\x98\x88\x88\x88eUeVx\x88\x87\x88g\x88\x86xx\x88\x87\x88\x86o\xf9\xff\x87w\x7f\xff\xf2\xf7\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', - b'\xf1\x87LDLVAA4777834HH1\x98\x88x\x87\x87wwwx\x88\x87\x88x\x99\x97\x89x\x88\x97\x88\x86o\xfa\xff\x86fO\xff\x1d9\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', - b'\xf1\x87LDLVAA5194534HH1ffvguUUUx\x88\xa7\x88h\x99\x96\x89x\x88\x97\x88ro\xf9\xff\x98wo\xff\xaaM\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', - b'\xf1\x87LDLVAA5949924HH1\xa9\x99y\x97\x87wwwx\x99\x97\x89x\x99\xa7\x89x\x99\xa7\x89\x87_\xfa\xffeD?\xff\xf1\xfd\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', - b'\xf1\x87LDLVBN560098KF26\x86fff\x87vgfg\x88\x96xfw\x86gfw\x86g\x95\xf6\xffeU_\xff\x92c\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB2\xafL]\xe7', - b'\xf1\x87LDLVBN602045KF26\xb9\x99\x89\x98\x97vwgy\xaa\xb7\x9af\x88\x96hw\x99\xa7y\xa9\x7f\xf5\xff\x99w\x7f\xff,\xd3\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN628911KF26\xa9\x99\x89\x98\x98\x88\x88\x88y\x99\xa7\x99fw\x86gw\x88\x87x\x83\x7f\xf6\xff\x98wo\xff2\xda\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN645817KF37\x87www\x98\x87xwx\x99\x97\x89\x99\x99\x99\x99g\x88\x96x\xb6_\xf7\xff\x98fo\xff\xe2\x86\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN662115KF37\x98\x88\x88\x88\xa8\x88\x88\x88x\x99\x97\x89x\x99\xa7\x89\x88\x99\xa8\x89\x88\x7f\xf7\xfffD_\xff\xdc\x84\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN667933KF37\xb9\x99\x89\x98\xb9\x99\x99\x99x\x88\x87\x88w\x88\x87x\x88\x88\x98\x88\xcbo\xf7\xffe3/\xffQ!\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN673087KF37\x97www\x86fvgx\x99\x97\x89\x99\xaa\xa9\x9ag\x88\x86x\xe9_\xf8\xff\x98w\x7f\xff"\xad\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN673841KF37\x98\x88x\x87\x86g\x86xy\x99\xa7\x99\x88\x99\xa8\x89w\x88\x97xdo\xf5\xff\x98\x88\x8f\xffT\xec\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN681363KF37\x98\x88\x88\x88\x97x\x87\x88y\xaa\xa7\x9a\x88\x88\x98\x88\x88\x88\x88\x88vo\xf6\xffvD\x7f\xff%v\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN713782KF37\x99\x99y\x97\x98\x88\x88\x88x\x88\x97\x88\x88\x99\x98\x89\x88\x99\xa8\x89\x87o\xf7\xffeU?\xff7,\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN713890KF26\xb9\x99\x89\x98\xa9\x99\x99\x99x\x99\x97\x89\x88\x99\xa8\x89\x88\x99\xb8\x89Do\xf7\xff\xa9\x88o\xffs\r\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN733215KF37\x99\x98y\x87\x97wwwi\x99\xa6\x99x\x99\xa7\x89V\x88\x95h\x86o\xf7\xffeDO\xff\x12\xe7\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN750044KF37\xca\xa9\x8a\x98\xa7wwwy\xaa\xb7\x9ag\x88\x96x\x88\x99\xa8\x89\xb9\x7f\xf6\xff\xa8w\x7f\xff\xbe\xde\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN752612KF37\xba\xaa\x8a\xa8\x87w\x87xy\xaa\xa7\x9a\x88\x99\x98\x89x\x88\x97\x88\x96o\xf6\xffvU_\xffh\x1b\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN755553KF37\x87xw\x87\x97w\x87xy\x99\xa7\x99\x99\x99\xa9\x99Vw\x95gwo\xf6\xffwUO\xff\xb5T\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08', - b'\xf1\x87LDLVBN757883KF37\x98\x87xw\x98\x87\x88xy\xaa\xb7\x9ag\x88\x96x\x89\x99\xa8\x99e\x7f\xf6\xff\xa9\x88o\xff5\x15\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', - b'\xf1\x87LDMVBN778156KF37\x87vWe\xa9\x99\x99\x99y\x99\xb7\x99\x99\x99\x99\x99x\x99\x97\x89\xa8\x7f\xf8\xffwf\x7f\xff\x82_\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', - b'\xf1\x87LDMVBN780576KF37\x98\x87hv\x97x\x97\x89x\x99\xa7\x89\x88\x99\x98\x89w\x88\x97x\x98\x7f\xf7\xff\xba\x88\x8f\xff\x1e0\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', - b'\xf1\x87LDMVBN783485KF37\x87www\x87vwgy\x99\xa7\x99\x99\x99\xa9\x99Vw\x95g\x89_\xf6\xff\xa9w_\xff\xc5\xd6\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', - b'\xf1\x87LDMVBN811844KF37\x87vwgvfffx\x99\xa7\x89Vw\x95gg\x88\xa6xe\x8f\xf6\xff\x97wO\xff\t\x80\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', - b'\xf1\x87LDMVBN830601KF37\xa7www\xa8\x87xwx\x99\xa7\x89Uw\x85Ww\x88\x97x\x88o\xf6\xff\x8a\xaa\x7f\xff\xe2:\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB4\xd6\xe8\xd7\xa6', - b'\xf1\x87LDMVBN848789KF37\x87w\x87x\x87w\x87xy\x99\xb7\x99\x87\x88\x98x\x88\x99\xa8\x89\x87\x7f\xf6\xfffUo\xff\xe3!\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN851595KF37\x97wgvvfffx\x99\xb7\x89\x88\x99\x98\x89\x87\x88\x98x\x99\x7f\xf7\xff\x97w\x7f\xff@\xf3\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN873175KF26\xa8\x88\x88\x88vfVex\x99\xb7\x89\x88\x99\x98\x89x\x88\x97\x88f\x7f\xf7\xff\xbb\xaa\x8f\xff,\x04\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN879401KF26veVU\xa8\x88\x88\x88g\x88\xa6xVw\x95gx\x88\xa7\x88v\x8f\xf9\xff\xdd\xbb\xbf\xff\xb3\x99\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN881314KF37\xa8\x88h\x86\x97www\x89\x99\xa8\x99w\x88\x97xx\x99\xa7\x89\xca\x7f\xf8\xff\xba\x99\x8f\xff\xd8v\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN888651KF37\xa9\x99\x89\x98vfff\x88\x99\x98\x89w\x99\xa7y\x88\x88\x98\x88D\x8f\xf9\xff\xcb\x99\x8f\xff\xa5\x1e\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN889419KF37\xa9\x99y\x97\x87w\x87xx\x88\x97\x88w\x88\x97x\x88\x99\x98\x89e\x9f\xf9\xffeUo\xff\x901\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN895969KF37vefV\x87vgfx\x99\xa7\x89\x99\x99\xb9\x99f\x88\x96he_\xf7\xffxwo\xff\x14\xf9\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDMVBN899222KF37\xa8\x88x\x87\x97www\x98\x99\x99\x89\x88\x99\x98\x89f\x88\x96hdo\xf7\xff\xbb\xaa\x9f\xff\xe2U\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b"\xf1\x87LBLUFN622950KF36\xa8\x88\x88\x88\x87w\x87xh\x99\x96\x89\x88\x99\x98\x89\x88\x99\x98\x89\x87o\xf6\xff\x98\x88o\xffx'\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8", - b'\xf1\x87LDMVBN950669KF37\x97www\x96fffy\x99\xa7\x99\xa9\x99\xaa\x99g\x88\x96x\xb8\x8f\xf9\xffTD/\xff\xa7\xcb\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - b'\xf1\x87LDLVAA4478824HH1\x87wwwvfvg\x89\x99\xa8\x99w\x88\x87x\x89\x99\xa8\x99\xa6o\xfa\xfffU/\xffu\x92\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', - b'\xf1\x87LDMVBN871852KF37\xb9\x99\x99\x99\xa8\x88\x88\x88y\x99\xa7\x99x\x99\xa7\x89\x88\x88\x98\x88\x89o\xf7\xff\xaa\x88o\xff\x0e\xed\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', - ], - }, - CAR.VELOSTER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', - b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816V8RAC00121.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x01TJS-JNU06F200H0A', - b'\x01TJS-JDK06F200H0A', - b'391282BJF5 ', - ], - (Ecu.eps, 0x7d4, None): [b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', - b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\xba\x02\xb8\x80', - b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16NS1\x00\x00\x00\x00', - b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJS0T16KS2\016\xba\036\xa2', - ], - }, - CAR.GENESIS_G70: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB2\x11\x1am\xda', - b'\xf1\x87VDJLT17895112DN4\x88fVf\x99\x88\x88\x88\x87fVe\x88vhwwUFU\x97eFex\x99\xff\xb7\x82\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB2\x11\x1am\xda', - ], - }, - CAR.GENESIS_G70_2020: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87VCJLP18407832DN3\x88vXfvUVT\x97eFU\x87d7v\x88eVeveFU\x89\x98\x7f\xff\xb2\xb0\xf1\x81E25\x00\x00\x00', - b'\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB4\xecE\xefL', - b'\xf1\x87VDKLT18912362DN4wfVfwefeveVUwfvw\x88vWfvUFU\x89\xa9\x8f\xff\x87w\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB4\xecE\xefL', - b'\xf1\x87VDJLC18480772DK9\x88eHfwfff\x87eFUeDEU\x98eFe\x86T5DVyo\xff\x87s\xf1\x81E25\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33KB5\x9f\xa5&\x81', - b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T20KB3Wuvz', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81640J0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81606G2051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.GENESIS_G80: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', - b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SDH0T33NH4\xd7O\x9e\xc9', - b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00TDH0G38NH3:-\xa9n', - b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0G38NH2j\x9dA\x1c', - b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0T33NH3\x97\xe6\xbc\xb8', - b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0G33KH2\xae\xde\xd5!', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x81640A4051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.GENESIS_G90: { - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87VDGMD15352242DD3w\x87gxwvgv\x87wvw\x88wXwffVfffUfw\x88o\xff\x06J\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcshcm49 E14\x00\x00\x00\x00\x00\x00\x00SHI0G50NB1tc5\xb7', - b'\xf1\x87VDGMD15866192DD3x\x88x\x89wuFvvfUf\x88vWwgwwwvfVgx\x87o\xff\xbc^\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcshcm49 E14\x00\x00\x00\x00\x00\x00\x00SHI0G50NB1tc5\xb7', - ], - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 '], - (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302'], - (Ecu.engine, 0x7e0, None): [b'\xf1\x810000000000\x00'], - }, - CAR.KONA: { - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', ], - (Ecu.abs, 0x7d1, None): [b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.engine, 0x7e0, None): [b'"\x01TOS-0NU06F301J02', ], - (Ecu.eps, 0x7d4, None): [b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', ], - (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', ], - (Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2VE051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VE051\x00\x00DOS4T16NS3\x00\x00\x00\x00', ], - }, - CAR.KIA_CEED: { - (Ecu.fwdRadar, 0x7D0, None): [b'\xf1\000CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', ], - (Ecu.eps, 0x7D4, None): [b'\xf1\000CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', ], - (Ecu.fwdCamera, 0x7C4, None): [b'\xf1\000CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', ], - (Ecu.engine, 0x7E0, None): [b'\001TCD-JECU4F202H0K', ], - (Ecu.transmission, 0x7E1, None): [ - b'\xf1\x816U2V7051\000\000\xf1\0006U2V0_C2\000\0006U2V7051\000\000DCD0T14US1\000\000\000\000', - b'\xf1\x816U2V7051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V7051\x00\x00DCD0T14US1U\x867Z', - ], - (Ecu.abs, 0x7D1, None): [b'\xf1\000CD ESC \003 102\030\b\005 58920-J7350', ], - }, - CAR.KIA_FORTE: { - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', - b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', - b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', - b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', - b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', - ], - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', - b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x01TBDM1NU06F200H01', - b'391182B945\x00', - b'\xf1\x81616F2051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x816VGRAH00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x8758900-M7AB0 \xf1\x816VQRAD00127.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x006V2B0_C2\x00\x006V2C6051\x00\x00CBD0N20NL1\x00\x00\x00\x00', - b'\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DBD0T16SS0\x00\x00\x00\x00', - b"\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DBD0T16SS0\xcf\x1e'\xc3", - ], - }, - CAR.KIA_K5_2021: { - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\000DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', - b'\xf1\x8799110L2000\xf1\000DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', - b'\xf1\x8799110L2100\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', - b'\xf1\x8799110L2100\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', - ], - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x8756310-L3110\xf1\000DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', - b'\xf1\x8756310-L3220\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', - b'\xf1\x8757700-L3000\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', - b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', - ], - (Ecu.abs, 0x7D1, None): [ - b'\xf1\000DL ESC \006 101 \004\002 58910-L3200', - b'\xf1\x8758910-L3200\xf1\000DL ESC \006 101 \004\002 58910-L3200', - b'\xf1\x8758910-L3800\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', - b'\xf1\x8758910-L3600\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', - b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', - b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', - b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', - ], - (Ecu.engine, 0x7E0, None): [ - b'\xf1\x87391212MKT0', - b'\xf1\x87391212MKV0', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82DLDWN5TMDCXXXJ1B', - b'\xf1\x81HM6M2_0a0_DQ0', - b'\xf1\x87391212MKT3', - ], - (Ecu.transmission, 0x7E1, None): [ - b'\xf1\000bcsh8p54 U913\000\000\000\000\000\000TDL2T16NB1ia\v\xb8', - b'\xf1\x87SALFEA5652514GK2UUeV\x88\x87\x88xxwg\x87ww\x87wwfwvd/\xfb\xffvU_\xff\x93\xd3\xf1\x81U913\000\000\000\000\000\000\xf1\000bcsh8p54 U913\000\000\000\000\000\000TDL2T16NB1ia\v\xb8', - b'\xf1\x87SALFEA6046104GK2wvwgeTeFg\x88\x96xwwwwffvfe?\xfd\xff\x86fo\xff\x97A\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB1ia\x0b\xb8', - b'\xf1\x87SCMSAA8572454GK1\x87x\x87\x88Vf\x86hgwvwvwwgvwwgT?\xfb\xff\x97fo\xffH\xb8\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL4T16NB05\x94t\x18', - b'\xf1\x87954A02N300\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 WDL3T25XXX730NS2b\x1f\xb8%', - b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL4T16NB05\x94t\x18', - b'\xf1\x00HT6TA261BLHT6TAB00A1SDL0C20KS0\x00\x00\x00\x00\x00\x00\\\x9f\xa5\x15', - b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL2T16NB2.\x13\xf6\xed', - ], - }, - CAR.KIA_K5_HEV_2020: { - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', - ], - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - ], - (Ecu.engine, 0x7E0, None): [ - b'\xf1\x87391162JLA0', - ], - (Ecu.transmission, 0x7E1, None): [ - b'\xf1\x00PSBG2323 E08\x00\x00\x00\x00\x00\x00\x00TDL2H20KA2\xe3\xc6cz', - b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDL2H20KA5T\xf2\xc9\xc2', - ], - }, - CAR.KONA_EV: { - (Ecu.abs, 0x7D1, None): [ - b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', - b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', - b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', - ], - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', - ], - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', - b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', - ], - }, - CAR.KONA_EV_2022: { - (Ecu.abs, 0x7D1, None): [ - b'\xf1\x8758520-K4010\xf1\x00OS IEB \x02 101 \x11\x13 58520-K4010', - b'\xf1\x8758520-K4010\xf1\x00OS IEB \x04 101 \x11\x13 58520-K4010', - b'\xf1\x8758520-K4010\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', - b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', - ], - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', - ], - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', - ], - }, - CAR.KONA_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', - ], - }, - CAR.KIA_NIRO_EV: { - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', - b'\xf1\x8799110Q4000\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', - b'\xf1\x8799110Q4100\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', - b'\xf1\x8799110Q4500\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', - b'\xf1\x8799110Q4600\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x8799110Q4600\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x8799110Q4600\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', - ], - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', - b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', - ], - }, - CAR.KIA_NIRO_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', - b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - }, - CAR.KIA_NIRO_PHEV: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91", - b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\x00\x00\x00\x00', - b'\xf1\x816U3H3051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H3051\x00\x00PDE0G16NS1\x00\x00\x00\x00', - b'\xf1\x816U3H3051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H3051\x00\x00PDE0G16NS1\x13\xcd\x88\x92', - b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PDE0G16NL2&[\xc3\x01', - ], - (Ecu.eps, 0x7D4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', - ], - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', - b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', - ], - }, - CAR.KIA_NIRO_HEV_2021: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HDE0G16NL3\x00\x00\x00\x00', - b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HDE0G16NL3\xb9\xd3\xfaW', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - ], - }, - CAR.KIA_SELTOS: { - (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110Q5100\xf1\000SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ',], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x8758910-Q5450\xf1\000SP ESC \a 101\031\t\005 58910-Q5450', - b'\xf1\x8758910-Q5450\xf1\000SP ESC \t 101\031\t\005 58910-Q5450', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81616D2051\000\000\000\000\000\000\000\000', - b'\xf1\x81616D5051\000\000\000\000\000\000\000\000', - b'\001TSP2KNL06F100J0K', - b'\001TSP2KNL06F200J0K', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\000SP2 MDPS C 1.00 1.04 56300Q5200 ', - b'\xf1\000SP2 MDPS C 1.01 1.05 56300Q5200 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\000SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', - b'\xf1\000SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87CZLUB49370612JF7h\xa8y\x87\x99\xa7hv\x99\x97fv\x88\x87x\x89x\x96O\xff\x88\xff\xff\xff.@\xf1\x816V2C2051\000\000\xf1\0006V2B0_C2\000\0006V2C2051\000\000CSP4N20NS3\000\000\000\000', - b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\000T0190XBL T01950A1 DSP2T16X4X950NS6\xd30\xa5\xb9', - b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\000T0190XBL T01950A1 DSP2T16X4X950NS8\r\xfe\x9c\x8b', - ], - }, - CAR.KIA_OPTIMA_G4: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6J0051\x00\x00\xf1\x006T6J0_C2\x00\x006T6J0051\x00\x00TJF0T20NSB\x00\x00\x00\x00', - ], - }, - CAR.KIA_OPTIMA_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', - b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW', - b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\xca3\xeb.', - b'\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DJF0T16NL2\x9eA\x80\x01', - b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\x00\x00\x00\x00', - b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW', - b'\xf1\x816U2VA051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\xca3\xeb.', - b'\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DJF0T16NL2\x9eA\x80\x01', - b'\xf1\x816U2VA051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\x00\x00\x00\x00', - b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B8051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B8051\x00\x00TJFSG24NH27\xa7\xc2\xb4', - ], - }, - CAR.KIA_OPTIMA_H: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', - ], - }, - CAR.KIA_OPTIMA_H_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.ELANTRA: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', - b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x006T6K0_C2\x00\x006T6S2051\x00\x00TAD0N20NSD(\xfcA\x9d', - b'\xf1\x006T6K0_C2\x00\x006T6S2051\x00\x00TAD0N20NSD\x00\x00\x00\x00', - b'\xf1\x006T6J0_C2\x00\x006T6F0051\x00\x00TAD0N20NS2\x00\x00\x00\x00', - b'\xf1\x006T6J0_C2\x00\x006T6F0051\x00\x00TAD0N20NS2\xc5\x92\x9e\x8a', - b'\xf1\x006T6J0_C2\x00\x006T6F0051\x00\x00TAD0N20SS2.~\x90\x87', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8161698051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x8161657051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816165D051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816165E051\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', - b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', - b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', - ], - }, - CAR.ELANTRA_GT_I30: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', - b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DPD0H16NS0e\x0e\xcd\x8e', - b'\xf1\x006U2U0_C2\x00\x006U2T0051\x00\x00DPD0D16KS0u\xce\x1fk', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', - b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', - b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', - b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', - ], - }, - CAR.ELANTRA_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', - b'\xf1\x8799110AA000\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', - b'\xf1\x8799110AA000\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', - b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', - b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', - b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800\xf1\xa01.01', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\xe8\xba\xce\xfa', - b'\xf1\x87CXMQFM2135005JB2E\xb9\x89\x98W\xa9y\x97h\xa9\x98\x99wxvwh\x87\177\xffx\xff\xff\xff,,\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', - b'\xf1\x87CXMQFM1916035JB2\x88vvgg\x87Wuwgev\xa9\x98\x88\x98h\x99\x9f\xffh\xff\xff\xff\xa5\xee\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', - b'\xf1\x87CXLQF40189012JL2f\x88\x86\x88\x88vUex\xb8\x88\x88\x88\x87\x88\x89fh?\xffz\xff\xff\xff\x08z\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', - b'\xf1\x87CXMQFM2728305JB2E\x97\x87xw\x87vwgw\x84x\x88\x88w\x89EI\xbf\xff{\xff\xff\xff\xe6\x0e\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', - b'\xf1\x87CXMQFM3806705JB2\x89\x87wwx\x88g\x86\x99\x87\x86xwwv\x88yv\x7f\xffz\xff\xff\xffV\x15\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x82CNCWD0AMFCXCSFFA', - b'\xf1\x81HM6M2_0a0_FF0', - b'\xf1\x82CNCVD0AMFCXCSFFB', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_G80', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_HC0', - ], - }, - CAR.ELANTRA_HEV_2021: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', - b'\xf1\000CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', - b'\xf1\x8799110BY000\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', - b'\xf1\x8756310/BY050\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', - b'\xf1\x8756310/BY050\xf1\000CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', - b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa', - b'\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\000\000\000\000', - b'\xf1\x816U3K3051\000\000\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa', - b'\xf1\x816U3K3051\x00\x00\xf1\x006U3L0_C2\x00\x006U3K3051\x00\x00HCN0G16NS0\x00\x00\x00\x00', - b'\xf1\x006U3L0_C2\x00\x006U3K9051\x00\x00HCN0G16NS1\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x816H6G8051\x00\x00\x00\x00\x00\x00\x00\x00', - ] - }, - CAR.KONA_HEV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HOS0G16DS1\x16\xc7\xb0\xd9', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', - ] - }, - CAR.SONATA_HYBRID: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', - b'\xf1\x8799110L5000\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', - b'\xf1\000DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', - b'\xf1\x8799110L5000\xf1\000DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x8756310-L5500\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', - b'\xf1\x8756310-L5450\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', - b'\xf1\x8756310-L5450\xf1\000DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', - b'\xf1\x8756310L5450\x00\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\000DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\000PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TDN2H20SA6N\xc2\xeeW', - b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E09\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2323 E09\x00\x00\x00\x00\x00\x00\x00TDN2H20SA5\x97R\x88\x9e', - b'\xf1\000PSBG2323 E09\000\000\000\000\000\000\000TDN2H20SA5\x97R\x88\x9e', - b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDN2H20SA7\x1a3\xf9\xab', - b'\xf1\x87PCU\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDN2H20SA7\x1a3\xf9\xab', - b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TDN2H20SA6N\xc2\xeeW', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x87391162J012', - b'\xf1\x87391162J013', - b'\xf1\x87391162J014', - b'\xf1\x87391062J002', - ], - }, - CAR.KIA_SORENTO: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01' - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330' - ], - (Ecu.fwdRadar, 0x7D0, None): [ - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ' - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87LDKUAA0348164HE3\x87www\x87www\x88\x88\xa8\x88w\x88\x97xw\x88\x97x\x86o\xf8\xff\x87f\x7f\xff\x15\xe0\xf1\x81U811\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U811\x00\x00\x00\x00\x00\x00TUM4G33NL3V|DG' - ], - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00' - ], - }, - CAR.KIA_SORENTO_PHEV_4TH_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', - ] - }, - CAR.KIA_EV6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', - ], - }, - CAR.IONIQ_5: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', - ], - }, - CAR.IONIQ_6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', - b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', - ], - }, - CAR.TUCSON_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', - ], - }, - CAR.TUCSON_HYBRID_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', - b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', - ], - }, - CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', - ], - }, - CAR.SANTA_CRUZ_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', - ], - }, - CAR.KIA_SPORTAGE_5TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', - ], - }, - CAR.GENESIS_GV70_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', - ], - }, - CAR.GENESIS_GV60_EV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', - ], - }, - CAR.KIA_SORENTO_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', - ], - }, - CAR.KIA_NIRO_HEV_2ND_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - }, - CAR.GENESIS_GV80: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', - ], - }, - CAR.KIA_CARNIVAL_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', - ], - }, - CAR.KIA_SORENTO_HEV_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', - ], - }, - CAR.KIA_K8_HEV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', - ], - }, -} CHECKSUM = { "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, @@ -2108,14 +533,13 @@ CAN_GEARS = { "use_tcu_gears": {CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, } -CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.IONIQ_6, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, - CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, +CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.IONIQ_6, CAR.TUCSON_4TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_NIRO_HEV_2ND_GEN, CAR.KIA_NIRO_EV_2ND_GEN, - CAR.GENESIS_GV80, CAR.KIA_CARNIVAL_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KONA_EV_2ND_GEN, CAR.KIA_K8_HEV_1ST_GEN} + CAR.GENESIS_GV80, CAR.KIA_CARNIVAL_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KONA_EV_2ND_GEN, CAR.KIA_K8_HEV_1ST_GEN, + CAR.STARIA_4TH_GEN} # The radar does SCC on these cars when HDA I, rather than the camera -CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.GENESIS_GV80, - CAR.KIA_CARNIVAL_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN} +CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.GENESIS_GV80, CAR.KIA_CARNIVAL_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN} # These CAN FD cars do not accept communication control to disable the ADAS ECU, # responds with 0x7F2822 - 'conditions not correct' @@ -2126,10 +550,8 @@ CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } # these cars use a different gas signal HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, - CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.TUCSON_HYBRID_4TH_GEN, - CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_K5_HEV_2020, CAR.KIA_NIRO_HEV_2ND_GEN, - CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.KIA_K8_HEV_1ST_GEN, - CAR.AZERA_HEV_6TH_GEN} + CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KIA_K5_HEV_2020, + CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.AZERA_HEV_6TH_GEN, CAR.KIA_NIRO_PHEV_2022} EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5, CAR.IONIQ_6, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KONA_EV_2ND_GEN} @@ -2194,14 +616,11 @@ DBC = { CAR.KIA_EV6: dbc_dict('hyundai_canfd', None), CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'), CAR.TUCSON_4TH_GEN: dbc_dict('hyundai_canfd', None), - CAR.TUCSON_HYBRID_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.IONIQ_5: dbc_dict('hyundai_canfd', None), CAR.IONIQ_6: dbc_dict('hyundai_canfd', None), CAR.SANTA_CRUZ_1ST_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_SPORTAGE_5TH_GEN: dbc_dict('hyundai_canfd', None), - CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: dbc_dict('hyundai_canfd', None), CAR.GENESIS_GV70_1ST_GEN: dbc_dict('hyundai_canfd', None), - CAR.KIA_SORENTO_PHEV_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.GENESIS_GV60_EV_1ST_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_SORENTO_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_NIRO_HEV_2ND_GEN: dbc_dict('hyundai_canfd', None), @@ -2212,4 +631,6 @@ DBC = { CAR.KONA_EV_2ND_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_K8_HEV_1ST_GEN: dbc_dict('hyundai_canfd', None), CAR.CUSTIN_1ST_GEN: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_NIRO_PHEV_2022: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'), + CAR.STARIA_4TH_GEN: dbc_dict('hyundai_canfd', None), } diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 1b68b1dbcf..9767752edb 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,14 +1,15 @@ -import yaml +import json import os -import time import numpy as np +import tomllib from abc import abstractmethod, ABC -from typing import Any, Dict, Optional, Tuple, List, Callable +from enum import StrEnum +from typing import Any, Dict, Optional, Tuple, List, Callable, NamedTuple from cereal import car from openpilot.common.basedir import BASEDIR from openpilot.common.conversions import Conversions as CV -from openpilot.common.kalman.simple_kalman import KF1D, get_kalman_gain +from openpilot.common.simple_kalman import KF1D, get_kalman_gain from openpilot.common.numpy_fast import clip from openpilot.common.realtime import DT_CTRL from openpilot.selfdrive.car import apply_hysteresis, gen_empty_fingerprint, scale_rot_inertia, scale_tire_stiffness, STD_CARGO_KG @@ -19,28 +20,37 @@ from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel ButtonType = car.CarState.ButtonEvent.Type GearShifter = car.CarState.GearShifter EventName = car.CarEvent.EventName -TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, bool], float] MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS ACCEL_MAX = 2.0 ACCEL_MIN = -3.5 FRICTION_THRESHOLD = 0.3 -TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.yaml') -TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.yaml') -TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.yaml') +TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.toml') +TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.toml') +TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.toml') + + +class LatControlInputs(NamedTuple): + lateral_acceleration: float + roll_compensation: float + vego: float + aego: float + + +TorqueFromLateralAccelCallbackType = Callable[[LatControlInputs, car.CarParams.LateralTorqueTuning, float, float, bool, bool], float] def get_torque_params(candidate): - with open(TORQUE_SUBSTITUTE_PATH) as f: - sub = yaml.load(f, Loader=yaml.CSafeLoader) + with open(TORQUE_SUBSTITUTE_PATH, 'rb') as f: + sub = tomllib.load(f) if candidate in sub: candidate = sub[candidate] - with open(TORQUE_PARAMS_PATH) as f: - params = yaml.load(f, Loader=yaml.CSafeLoader) - with open(TORQUE_OVERRIDE_PATH) as f: - override = yaml.load(f, Loader=yaml.CSafeLoader) + with open(TORQUE_PARAMS_PATH, 'rb') as f: + params = tomllib.load(f) + with open(TORQUE_OVERRIDE_PATH, 'rb') as f: + override = tomllib.load(f) # Ensure no overlap if sum([candidate in x for x in [sub, params, override]]) > 1: @@ -124,17 +134,16 @@ class CarInterfaceBase(ABC): @staticmethod def get_steer_feedforward_default(desired_angle, v_ego): # Proportional to realigning tire momentum: lateral acceleration. - # TODO: something with lateralPlan.curvatureRates return desired_angle * (v_ego**2) def get_steer_feedforward_function(self): return self.get_steer_feedforward_default - def torque_from_lateral_accel_linear(self, lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: + def torque_from_lateral_accel_linear(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, + lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - return (lateral_accel_value / float(torque_params.latAccelFactor)) + friction + return (latcontrol_inputs.lateral_acceleration / float(torque_params.latAccelFactor)) + friction def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: return self.torque_from_lateral_accel_linear @@ -312,13 +321,14 @@ class RadarInterfaceBase(ABC): self.pts = {} self.delay = 0 self.radar_ts = CP.radarTimeStep + self.frame = 0 self.no_radar_sleep = 'NO_RADAR_SLEEP' in os.environ def update(self, can_strings): - ret = car.RadarData.new_message() - if not self.no_radar_sleep: - time.sleep(self.radar_ts) # radard runs on RI updates - return ret + self.frame += 1 + if (self.frame % int(100 * self.radar_ts)) == 0: + return car.RadarData.new_message() + return None class CarStateBase(ABC): @@ -346,7 +356,7 @@ class CarStateBase(ABC): def update_speed_kf(self, v_ego_raw): if abs(v_ego_raw - self.v_ego_kf.x[0][0]) > 2.0: # Prevent large accelerations when car starts at non zero speed - self.v_ego_kf.x = [[v_ego_raw], [0.0]] + self.v_ego_kf.set_x([[v_ego_raw], [0.0]]) v_ego_x = self.v_ego_kf.update(v_ego_raw) return float(v_ego_x[0]), float(v_ego_x[1]) @@ -433,9 +443,14 @@ class CarStateBase(ABC): return None +INTERFACE_ATTR_FILE = { + "FINGERPRINTS": "fingerprints", + "FW_VERSIONS": "fingerprints", +} + # interface-specific helpers -def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: bool = False) -> Dict[str, Any]: +def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: bool = False) -> Dict[str | StrEnum, Any]: # read all the folders in selfdrive/car and return a dict where: # - keys are all the car models or brand names # - values are attr values from all car folders @@ -443,7 +458,7 @@ def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: boo for car_folder in sorted([x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]): try: brand_name = car_folder.split('/')[-1] - brand_values = __import__(f'openpilot.selfdrive.car.{brand_name}.values', fromlist=[attr]) + brand_values = __import__(f'openpilot.selfdrive.car.{brand_name}.{INTERFACE_ATTR_FILE.get(attr, "values")}', fromlist=[attr]) if hasattr(brand_values, attr) or not ignore_none: attr_data = getattr(brand_values, attr, None) else: @@ -459,3 +474,35 @@ def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: boo pass return result + + +class NanoFFModel: + def __init__(self, weights_loc: str, platform: str): + self.weights_loc = weights_loc + self.platform = platform + self.load_weights(platform) + + def load_weights(self, platform: str): + with open(self.weights_loc, 'r') as fob: + self.weights = {k: np.array(v) for k, v in json.load(fob)[platform].items()} + + def relu(self, x: np.ndarray): + return np.maximum(0.0, x) + + def forward(self, x: np.ndarray): + assert x.ndim == 1 + x = (x - self.weights['input_norm_mat'][:, 0]) / (self.weights['input_norm_mat'][:, 1] - self.weights['input_norm_mat'][:, 0]) + x = self.relu(np.dot(x, self.weights['w_1']) + self.weights['b_1']) + x = self.relu(np.dot(x, self.weights['w_2']) + self.weights['b_2']) + x = self.relu(np.dot(x, self.weights['w_3']) + self.weights['b_3']) + x = np.dot(x, self.weights['w_4']) + self.weights['b_4'] + return x + + def predict(self, x: List[float], do_sample: bool = False): + x = self.forward(np.array(x)) + if do_sample: + pred = np.random.laplace(x[0], np.exp(x[1]) / self.weights['temperature']) + else: + pred = x[0] + pred = pred * (self.weights['output_norm_mat'][1] - self.weights['output_norm_mat'][0]) + self.weights['output_norm_mat'][0] + return pred diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index adbc598ea6..678fe9ea46 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -3,13 +3,16 @@ from collections import defaultdict from functools import partial import cereal.messaging as messaging -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.boardd.boardd import can_list_to_can_capnp +from openpilot.selfdrive.car.fw_query_definitions import AddrType from panda.python.uds import CanClient, IsoTpMessage, FUNCTIONAL_ADDRS, get_rx_addr_for_tx_addr class IsoTpParallelQuery: - def __init__(self, sendcan, logcan, bus, addrs, request, response, response_offset=0x8, functional_addrs=None, debug=False, response_pending_timeout=10): + def __init__(self, sendcan: messaging.PubSocket, logcan: messaging.SubSocket, bus: int, addrs: list[int] | list[AddrType], + request: list[bytes], response: list[bytes], response_offset: int = 0x8, + functional_addrs: list[int] | None = None, debug: bool = False, response_pending_timeout: float = 10) -> None: self.sendcan = sendcan self.logcan = logcan self.bus = bus @@ -24,7 +27,7 @@ class IsoTpParallelQuery: assert tx_addr not in FUNCTIONAL_ADDRS, f"Functional address should be defined in functional_addrs: {hex(tx_addr)}" self.msg_addrs = {tx_addr: get_rx_addr_for_tx_addr(tx_addr[0], rx_offset=response_offset) for tx_addr in real_addrs} - self.msg_buffer = defaultdict(list) + self.msg_buffer: dict[int, list[tuple[int, int, bytes, int]]] = defaultdict(list) def rx(self): """Drain can socket and sort messages into buffers based on address""" @@ -63,7 +66,7 @@ class IsoTpParallelQuery: messaging.drain_sock_raw(self.logcan) self.msg_buffer = defaultdict(list) - def _create_isotp_msg(self, tx_addr, sub_addr, rx_addr): + def _create_isotp_msg(self, tx_addr: int, sub_addr: int | None, rx_addr: int): can_client = CanClient(self._can_tx, partial(self._can_rx, rx_addr, sub_addr=sub_addr), tx_addr, rx_addr, self.bus, sub_addr=sub_addr, debug=self.debug) @@ -73,7 +76,7 @@ class IsoTpParallelQuery: # as well as reduces chances we process messages from previous queries return IsoTpMessage(can_client, timeout=0, separation_time=0.01, debug=self.debug, max_len=max_len) - def get_data(self, timeout, total_timeout=60.): + def get_data(self, timeout: float, total_timeout: float = 60.) -> dict[AddrType, bytes]: self._drain_rx() # Create message objects diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index 1f7846ca06..c0819592d4 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -32,7 +32,7 @@ class CarState(CarStateBase): # Match panda speed reading speed_kph = cp.vl["ENGINE_DATA"]["SPEED"] - ret.standstill = speed_kph < .1 + ret.standstill = speed_kph <= .1 can_gear = int(cp.vl["GEAR"]["GEAR"]) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) diff --git a/selfdrive/car/mazda/fingerprints.py b/selfdrive/car/mazda/fingerprints.py new file mode 100644 index 0000000000..292f407935 --- /dev/null +++ b/selfdrive/car/mazda/fingerprints.py @@ -0,0 +1,260 @@ +from cereal import car +from openpilot.selfdrive.car.mazda.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.CX5_2022: { + (Ecu.eps, 0x730, None): [ + b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.CX5: { + (Ecu.eps, 0x730, None): [ + b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2E-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.CX9: { + (Ecu.eps, 0x730, None): [ + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA3: { + (Ecu.eps, 0x730, None): [ + b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA6: { + (Ecu.eps, 0x730, None): [ + b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GFBC-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX4F-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GDDM-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH3-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.CX9_2021: { + (Ecu.eps, 0x730, None): [ + b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, +} diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 1547f69b04..b43ab3df66 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -67,278 +67,15 @@ class Buttons: FW_QUERY_CONFIG = FwQueryConfig( requests=[ - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - ), - # Log responses on powertrain bus + # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 Request( [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], bus=0, - logging=True, ), ], ) -FW_VERSIONS = { - CAR.CX5_2022: { - (Ecu.eps, 0x730, None): [ - b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.CX5: { - (Ecu.eps, 0x730, None): [ - b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - - CAR.CX9 : { - (Ecu.eps, 0x730, None): [ - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - - CAR.MAZDA3: { - (Ecu.eps, 0x730, None): [ - b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - - ], - (Ecu.engine, 0x7e0, None): [ - b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - - CAR.MAZDA6: { - (Ecu.eps, 0x730, None): [ - b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GFBC-3210X-A-00\000\000\000\000\000\000\000\000\000', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX4F-188K2-D\000\000\000\000\000\000\000\000\000\000\000\000', - b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\000\000\000\000\000\000\000\000\000\000\000\000', - ], - (Ecu.abs, 0x760, None): [ - b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GDDM-437K2-A\000\000\000\000\000\000\000\000\000\000\000\000', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\000\000\000\000\000\000\000\000\000\000\000\000', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH3-21PS1-D\000\000\000\000\000\000\000\000\000\000\000\000', - b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - - CAR.CX9_2021 : { - (Ecu.eps, 0x730, None): [ - b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - } -} - DBC = { CAR.CX5: dbc_dict('mazda_2017', None), diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index c7821bdb97..2e4ac43033 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -22,7 +22,7 @@ class CarInterface(CarInterfaceBase): def _update(self, c): self.sm.update(0) - gps_sock = 'gpsLocationExternal' if self.sm.rcv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' + gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' ret = car.CarState.new_message() ret.vEgo = self.sm[gps_sock].speed diff --git a/selfdrive/car/nissan/fingerprints.py b/selfdrive/car/nissan/fingerprints.py new file mode 100644 index 0000000000..19267ded46 --- /dev/null +++ b/selfdrive/car/nissan/fingerprints.py @@ -0,0 +1,119 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.nissan.values import CAR + +Ecu = car.CarParams.Ecu + +FINGERPRINTS = { + CAR.XTRAIL: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 + }, + { + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 + }], + CAR.LEAF: [{ + 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 + }, + { + 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 + }], + CAR.LEAF_IC: [{ + 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 + }], + CAR.ROGUE: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.ALTIMA: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], +} + +FW_VERSIONS = { + CAR.ALTIMA: { + (Ecu.fwdCamera, 0x707, None): [ + b'284N86CA1D', + ], + (Ecu.eps, 0x742, None): [ + b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', + ], + (Ecu.engine, 0x7e0, None): [ + b'237109HE2B', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U29HE0A', + ], + }, + CAR.LEAF: { + (Ecu.abs, 0x740, None): [ + b'476605SA1C', + b'476605SA7D', + b'476605SC2D', + b'476606WK7B', + b'476606WK9B', + ], + (Ecu.eps, 0x742, None): [ + b'5SA2A\x99A\x05\x02N123F\x15b\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SA2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SN2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.fwdCamera, 0x707, None): [ + b'5SA0ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', + b'5SA2ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', + b'6WK2ADB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', + b'6WK2BDB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', + b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U25SA3C', + b'284U25SP0C', + b'284U25SP1C', + b'284U26WK0A', + b'284U26WK0C', + ], + }, + CAR.LEAF_IC: { + (Ecu.fwdCamera, 0x707, None): [ + b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', + b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', + b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', + ], + (Ecu.abs, 0x740, None): [ + b'476605SD2E', + b'476605SH1D', + b'476605SK2A', + ], + (Ecu.eps, 0x742, None): [ + b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U25SF0C', + b'284U25SH3A', + b'284U25SK2D', + ], + }, + CAR.XTRAIL: { + (Ecu.fwdCamera, 0x707, None): [ + b'284N86FR2A', + ], + (Ecu.abs, 0x740, None): [ + b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', + b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', + ], + (Ecu.eps, 0x742, None): [ + b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.combinationMeter, 0x743, None): [ + b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.engine, 0x7e0, None): [ + b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U26FR0E', + ], + }, +} diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 474cb15e7f..d064ce894d 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -1,4 +1,3 @@ -# ruff: noqa: E501 from dataclasses import dataclass, field from enum import StrEnum from typing import Dict, List, Optional, Union @@ -46,41 +45,6 @@ CAR_INFO: Dict[str, Optional[Union[NissanCarInfo, List[NissanCarInfo]]]] = { CAR.ALTIMA: NissanCarInfo("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b])), } -FINGERPRINTS = { - CAR.XTRAIL: [ - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 - }, - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 - }, - ], - CAR.LEAF: [ - { - 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 - }, - # 2020 Leaf SV Plus - { - 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 - }, - ], - CAR.LEAF_IC: [ - { - 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 - }, - ], - CAR.ROGUE: [ - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }, - ], - CAR.ALTIMA: [ - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }, - ] -} - # Default diagnostic session NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) @@ -95,104 +59,37 @@ NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' NISSAN_RX_OFFSET = 0x20 FW_QUERY_CONFIG = FwQueryConfig( - requests=[ + requests=[request for bus, logging in ((0, False), (1, True)) for request in [ Request( [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + bus=bus, + logging=logging, ), Request( [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], rx_offset=NISSAN_RX_OFFSET, + bus=bus, + logging=logging, ), # Rogue's engine solely responds to this Request( [NISSAN_DIAGNOSTIC_REQUEST_KWP_2, NISSAN_VERSION_REQUEST_KWP], [NISSAN_DIAGNOSTIC_RESPONSE_KWP_2, NISSAN_VERSION_RESPONSE_KWP], + bus=bus, + logging=logging, ), Request( [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], rx_offset=NISSAN_RX_OFFSET, + bus=bus, + logging=logging, ), - ], + ]], ) -FW_VERSIONS = { - CAR.ALTIMA: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86CA1D', - ], - (Ecu.eps, 0x742, None): [ - b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'237109HE2B', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U29HE0A', - ], - }, - CAR.LEAF: { - (Ecu.abs, 0x740, None): [ - b'476606WK9B', - ], - (Ecu.eps, 0x742, None): [ - b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.fwdCamera, 0x707, None): [ - b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U26WK0C', - ], - }, - CAR.LEAF_IC: { - (Ecu.fwdCamera, 0x707, None): [ - b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', - b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - ], - (Ecu.abs, 0x740, None): [ - b'476605SH1D', - b'476605SK2A', - b'476605SD2E', - ], - (Ecu.eps, 0x742, None): [ - b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SH3A', - b'284U25SK2D', - b'284U25SF0C', - ], - }, - CAR.XTRAIL: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86FR2A', - ], - (Ecu.abs, 0x740, None): [ - b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', - b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', - ], - (Ecu.eps, 0x742, None): [ - b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.combinationMeter, 0x743, None): [ - b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U26FR0E', - ], - }, -} - DBC = { CAR.XTRAIL: dbc_dict('nissan_x_trail_2017_generated', None), CAR.LEAF: dbc_dict('nissan_leaf_2018_generated', None), diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index c277f012ab..cc8ce4f722 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -95,8 +95,8 @@ class CarController: else: if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, self.CP.openpilotLongitudinalControl, - CC.longActive, hud_control.leadVisible)) + can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, + self.CP.openpilotLongitudinalControl, CC.longActive, hud_control.leadVisible)) can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert, hud_control.leftLaneVisible, hud_control.rightLaneVisible, @@ -110,7 +110,8 @@ class CarController: can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg, self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm)) - can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, CC.enabled, cruise_brake)) + can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, + self.CP.openpilotLongitudinalControl, CC.longActive, cruise_brake)) can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd, self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle)) diff --git a/selfdrive/car/subaru/fingerprints.py b/selfdrive/car/subaru/fingerprints.py new file mode 100644 index 0000000000..90fa6093d9 --- /dev/null +++ b/selfdrive/car/subaru/fingerprints.py @@ -0,0 +1,550 @@ +from cereal import car +from openpilot.selfdrive.car.subaru.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.ASCENT: { + (Ecu.abs, 0x7b0, None): [ + b'\xa5 \x19\x02\x00', + b'\xa5 !\x02\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x05\xc0\xd0\x00', + b'\x85\xc0\xd0\x00', + b'\x95\xc0\xd0\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00d\xb9\x00\x00\x00\x00', + b'\x00\x00d\xb9\x1f@ \x10', + b'\x00\x00e@\x00\x00\x00\x00', + b'\x00\x00e@\x1f@ $', + b"\x00\x00e~\x1f@ '", + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbb,\xa0t\x07', + b'\xd1,\xa0q\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x00\xfe\xf7\x00\x00', + b'\x01\xfe\xf7\x00\x00', + b'\x01\xfe\xf9\x00\x00', + b'\x01\xfe\xfa\x00\x00', + ], + }, + CAR.ASCENT_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\xa5 #\x03\x00', + ], + (Ecu.eps, 0x746, None): [ + b'%\xc0\xd0\x11', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x05!\x08\x1dK\x05!\x08\x01/', + ], + (Ecu.engine, 0x7a2, None): [ + b'\xe5,\xa0P\x07', + ], + (Ecu.transmission, 0x7a3, None): [ + b'\x04\xfe\xf3\x00\x00', + ], + }, + CAR.LEGACY: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 \x02\x01', + b'\xa1 \x02\x02', + b'\xa1 \x03\x03', + b'\xa1 \x04\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x9b\xc0\x11\x00', + b'\x9b\xc0\x11\x02', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xde"a0\x07', + b'\xde,\xa0@\x07', + b'\xe2"aq\x07', + b'\xe2,\xa0@\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6\x05@\x00', + b'\xa5\xfe\xc7@\x00', + b'\xa7\xf6\x04@\x00', + b'\xa7\xfe\xc4@\x00', + ], + }, + CAR.IMPREZA: { + (Ecu.abs, 0x7b0, None): [ + b'z\x84\x19\x90\x00', + b'z\x94\x08\x90\x00', + b'z\x94\x08\x90\x01', + b'z\x94\x0c\x90\x00', + b'z\x94\x0c\x90\x01', + b'z\x94.\x90\x00', + b'z\x94?\x90\x00', + b'z\x9c\x19\x80\x01', + b'\xa2 \x185\x00', + b'\xa2 \x193\x00', + b'\xa2 \x194\x00', + b'\xa2 \x19`\x00', + ], + (Ecu.eps, 0x746, None): [ + b'z\xc0\x00\x00', + b'z\xc0\x04\x00', + b'z\xc0\x08\x00', + b'z\xc0\n\x00', + b'z\xc0\x0c\x00', + b'\x8a\xc0\x00\x00', + b'\x8a\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xf4\x00\x00\x00\x00', + b'\x00\x00c\xf4\x1f@ \x07', + b'\x00\x00d)\x00\x00\x00\x00', + b'\x00\x00d)\x1f@ \x07', + b'\x00\x00dd\x00\x00\x00\x00', + b'\x00\x00dd\x1f@ \x0e', + b'\x00\x00d\xb5\x1f@ \x0e', + b'\x00\x00d\xdc\x00\x00\x00\x00', + b'\x00\x00d\xdc\x1f@ \x0e', + b'\x00\x00e\x02\x1f@ \x14', + b'\x00\x00e\x1c\x00\x00\x00\x00', + b'\x00\x00e\x1c\x1f@ \x14', + b'\x00\x00e+\x00\x00\x00\x00', + b'\x00\x00e+\x1f@ \x14', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xaa\x00Bu\x07', + b'\xaa\x01bt\x07', + b'\xaa!`u\x07', + b'\xaa!au\x07', + b'\xaa!av\x07', + b'\xaa!aw\x07', + b'\xaa!dq\x07', + b'\xaa!ds\x07', + b'\xaa!dt\x07', + b'\xaaafs\x07', + b'\xbe!as\x07', + b'\xbe!at\x07', + b'\xbeacr\x07', + b'\xc5!`r\x07', + b'\xc5!`s\x07', + b'\xc5!ap\x07', + b'\xc5!ar\x07', + b'\xc5!as\x07', + b'\xc5!dr\x07', + b'\xc5!ds\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe3\xd0\x081\x00', + b'\xe3\xd5\x161\x00', + b'\xe3\xe5F1\x00', + b'\xe3\xf5\x06\x00\x00', + b'\xe3\xf5\x07\x00\x00', + b'\xe3\xf5C\x00\x00', + b'\xe3\xf5F\x00\x00', + b'\xe3\xf5G\x00\x00', + b'\xe4\xe5\x061\x00', + b'\xe4\xf5\x02\x00\x00', + b'\xe4\xf5\x07\x00\x00', + b'\xe5\xf5\x04\x00\x00', + b'\xe5\xf5$\x00\x00', + b'\xe5\xf5B\x00\x00', + ], + }, + CAR.IMPREZA_2020: { + (Ecu.abs, 0x7b0, None): [ + b'\xa2 \x193\x00', + b'\xa2 \x194\x00', + b'\xa2 `\x00', + b'\xa2 !3\x00', + b'\xa2 !`\x00', + b'\xa2 !i\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\n\xc0\x04\x00', + b'\n\xc0\x04\x01', + b'\x9a\xc0\x00\x00', + b'\x9a\xc0\x04\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eb\x1f@ "', + b'\x00\x00eq\x00\x00\x00\x00', + b'\x00\x00eq\x1f@ "', + b'\x00\x00e\x8f\x00\x00\x00\x00', + b'\x00\x00e\x8f\x1f@ )', + b'\x00\x00e\x92\x00\x00\x00\x00', + b'\x00\x00e\xa4\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xca!`0\x07', + b'\xca!`p\x07', + b'\xca!ap\x07', + b'\xca!f@\x07', + b'\xca!fp\x07', + b'\xcc!`p\x07', + b'\xcc!fp\x07', + b'\xcc"f0\x07', + b'\xe6!`@\x07', + b'\xe6!fp\x07', + b'\xe6"f0\x07', + b'\xe6"fp\x07', + b'\xf3"f@\x07', + b'\xf3"fp\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe6\xf5\x04\x00\x00', + b'\xe6\xf5$\x00\x00', + b'\xe6\xf5D0\x00', + b'\xe7\xf5\x04\x00\x00', + b'\xe7\xf5D0\x00', + b'\xe7\xf6B0\x00', + b'\xe9\xf5"\x00\x00', + b'\xe9\xf5B0\x00', + b'\xe9\xf6B0\x00', + b'\xe9\xf6F0\x00', + ], + }, + CAR.CROSSTREK_HYBRID: { + (Ecu.abs, 0x7b0, None): [ + b'\xa2 \x19e\x01', + b'\xa2 !e\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\n\xc2\x01\x00', + b'\x9a\xc2\x01\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00el\x1f@ #', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd7!`@\x07', + b'\xd7!`p\x07', + b'\xf4!`0\x07', + ], + }, + CAR.FORESTER: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 \x18\x14\x00', + b'\xa3 \x18&\x00', + b'\xa3 \x19\x14\x00', + b'\xa3 \x19&\x00', + b'\xa3 \x14\x00', + b'\xa3 \x14\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc0\x00\x00', + b'\x8d\xc0\x04\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e!\x00\x00\x00\x00', + b'\x00\x00e!\x1f@ \x11', + b'\x00\x00e^\x00\x00\x00\x00', + b'\x00\x00e^\x1f@ !', + b'\x00\x00e`\x1f@ ', + b'\x00\x00e\x97\x00\x00\x00\x00', + b'\x00\x00e\x97\x1f@ 0', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb6"`A\x07', + b'\xb6\xa2`A\x07', + b'\xcb"`@\x07', + b'\xcb"`p\x07', + b'\xcf"`0\x07', + b'\xcf"`p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1a\xe6B1\x00', + b'\x1a\xe6F1\x00', + b'\x1a\xf6B0\x00', + b'\x1a\xf6B`\x00', + b'\x1a\xf6F`\x00', + b'\x1a\xf6b0\x00', + b'\x1a\xf6b`\x00', + ], + }, + CAR.FORESTER_HYBRID: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 \x19T\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc2\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eY\x1f@ !', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd2\xa1`r\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1b\xa7@a\x00', + ], + }, + CAR.FORESTER_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'm\x97\x14@', + b'}\x97\x14@', + ], + (Ecu.eps, 0x746, None): [ + b'm\xc0\x10\x00', + b'}\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xe9\x00\x00\x00\x00', + b'\x00\x00c\xe9\x1f@ \x03', + b'\x00\x00d5\x1f@ \t', + b'\x00\x00d\xd3\x1f@ \t', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa7"@p\x07', + b'\xa7)\xa0q\x07', + b'\xba"@@\x07', + b'\xba"@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1a\xf6F`\x00', + b'\xda\xf2`\x80\x00', + b'\xda\xfd\xe0\x80\x00', + b'\xdc\xf2@`\x00', + b'\xdc\xf2``\x00', + b'\xdc\xf2`\x80\x00', + b'\xdc\xf2`\x81\x00', + ], + }, + CAR.LEGACY_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'[\x97D\x00', + b'[\xba\xc4\x03', + b'k\x97D\x00', + b'k\x9aD\x00', + b'{\x97D\x00', + ], + (Ecu.eps, 0x746, None): [ + b'K\xb0\x00\x01', + b'[\xb0\x00\x01', + b'k\xb0\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa0"@q\x07', + b'\xa0+@p\x07', + b'\xab*@r\x07', + b'\xab+@p\x07', + b'\xb4"@0\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xf2\x00`\x00', + b'\xbe\xf2\x00p\x00', + b'\xbe\xfb\xc0p\x00', + b'\xbf\xf2\x00\x80\x00', + b'\xbf\xfb\xc0\x80\x00', + ], + }, + CAR.OUTBACK_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'[\xba\xac\x03', + b'[\xf7\xac\x00', + b'[\xf7\xac\x03', + b'[\xf7\xbc\x03', + b'k\x97\xac\x00', + b'k\x9a\xac\x00', + b'{\x97\xac\x00', + b'{\x9a\xac\x00', + ], + (Ecu.eps, 0x746, None): [ + b'K\xb0\x00\x00', + b'K\xb0\x00\x02', + b'[\xb0\x00\x00', + b'k\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\x90\x1f@\x10\x0e', + b'\x00\x00c\x94\x00\x00\x00\x00', + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\xd1\x1f@\x10\x17', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa0"@\x80\x07', + b'\xa0*@q\x07', + b'\xa0*@u\x07', + b'\xa0+@@\x07', + b'\xa0bAq\x07', + b'\xab"@@\x07', + b'\xab"@s\x07', + b'\xab*@@\x07', + b'\xab+@@\x07', + b'\xb4"@0\x07', + b'\xb4"@p\x07', + b'\xb4"@r\x07', + b'\xb4+@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xf2@`\x00', + b'\xbd\xf2@\x81\x00', + b'\xbd\xfb\xe0\x80\x00', + b'\xbe\xf2@p\x00', + b'\xbe\xf2@\x80\x00', + b'\xbe\xfb\xe0p\x00', + b'\xbf\xe2@\x80\x00', + b'\xbf\xf2@\x80\x00', + b'\xbf\xfb\xe0b\x00', + ], + }, + CAR.OUTBACK_PREGLOBAL_2018: { + (Ecu.abs, 0x7b0, None): [ + b'\x8b\x97\xac\x00', + b'\x8b\x97\xbc\x00', + b'\x8b\x99\xac\x00', + b'\x8b\x9a\xac\x00', + b'\x9b\x97\xac\x00', + b'\x9b\x97\xbe\x10', + b'\x9b\x9a\xac\x00', + ], + (Ecu.eps, 0x746, None): [ + b'{\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00df\x1f@ \n', + b'\x00\x00d\x95\x00\x00\x00\x00', + b'\x00\x00d\x95\x1f@ \x0f', + b'\x00\x00d\xfe\x00\x00\x00\x00', + b'\x00\x00d\xfe\x1f@ \x15', + b'\x00\x00e\x19\x1f@ \x15', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb5"@P\x07', + b'\xb5"@p\x07', + b'\xb5+@@\x07', + b'\xb5b@1\x07', + b'\xb5q\xe0@\x07', + b'\xc4"@0\x07', + b'\xc4+@0\x07', + b'\xc4b@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbb\xf2@`\x00', + b'\xbb\xfb\xe0`\x00', + b'\xbc\xaf\xe0`\x00', + b'\xbc\xe2@\x80\x00', + b'\xbc\xf2@\x80\x00', + b'\xbc\xf2@\x81\x00', + b'\xbc\xfb\xe0`\x00', + b'\xbc\xfb\xe0\x80\x00', + ], + }, + CAR.OUTBACK: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 \x06\x00', + b'\xa1 \x06\x01', + b'\xa1 \x06\x02', + b'\xa1 \x07\x00', + b'\xa1 \x07\x02', + b'\xa1 \x07\x03', + b'\xa1 \x08\x00', + b'\xa1 \x08\x01', + b'\xa1 \x08\x02', + b'\xa1 "\t\x00', + b'\xa1 "\t\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x1b\xc0\x10\x00', + b'\x9b\xc0\x10\x00', + b'\x9b\xc0\x10\x02', + b'\x9b\xc0 \x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', + b'\x00\x00eJ\x00\x1f@ \x19\x00', + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', + b'\x00\x00e\x9a\x00\x1f@ 1\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbc"`@\x07', + b'\xbc"`q\x07', + b'\xbc,\xa0q\x07', + b'\xbc,\xa0u\x07', + b'\xde"`0\x07', + b'\xde,\xa0@\x07', + b'\xe2"`0\x07', + b'\xe2"`p\x07', + b'\xe2"`q\x07', + b'\xe3,\xa0@\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6D@\x00', + b'\xa5\xfe\xf6@\x00', + b'\xa5\xfe\xf7@\x00', + b'\xa5\xfe\xf8@\x00', + b'\xa7\x8e\xf40\x00', + b'\xa7\xf6D@\x00', + b'\xa7\xfe\xf4@\x00', + ], + }, + CAR.FORESTER_2022: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 !v\x00', + b'\xa3 !x\x00', + b'\xa3 "v\x00', + b'\xa3 "x\x00', + ], + (Ecu.eps, 0x746, None): [ + b'-\xc0\x040', + b'-\xc0%0', + b'=\xc0%\x02', + b'=\xc04\x02', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x04!\x01\x1eD\x07!\x00\x04,', + b'\x04!\x08\x01.\x07!\x08\x022', + b'\r!\x08\x017\n!\x08\x003', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd5"`0\x07', + b'\xd5"a0\x07', + b'\xf1"`q\x07', + b'\xf1"aq\x07', + b'\xfa"ap\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1d\x86B0\x00', + b'\x1d\xf6B0\x00', + b'\x1e\x86B0\x00', + b'\x1e\x86F0\x00', + b'\x1e\xf6D0\x00', + ], + }, + CAR.OUTBACK_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 #\x14\x00', + b'\xa1 #\x17\x00', + ], + (Ecu.eps, 0x746, None): [ + b'+\xc0\x10\x11\x00', + b'+\xc0\x12\x11\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\t!\x08\x046\x05!\x08\x01/', + ], + (Ecu.engine, 0x7a2, None): [ + b'\xed,\xa0q\x07', + b'\xed,\xa2q\x07', + ], + (Ecu.transmission, 0x7a3, None): [ + b'\xa8\x8e\xf41\x00', + b'\xa8\xfe\xf41\x00', + ], + }, +} diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 79576f6433..1296aead5e 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -118,11 +118,11 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"unknown car: {candidate}") - #ret.experimentalLongitudinalAvailable = candidate not in (GLOBAL_GEN2 | PREGLOBAL_CARS | LKAS_ANGLE | HYBRID_CARS) + ret.experimentalLongitudinalAvailable = candidate not in (GLOBAL_GEN2 | PREGLOBAL_CARS | LKAS_ANGLE | HYBRID_CARS) ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable if candidate in GLOBAL_GEN2 and ret.openpilotLongitudinalControl: - ret.flags |= SubaruFlags.DISABLE_EYESIGHT + ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value if ret.openpilotLongitudinalControl: ret.longitudinalTuning.kpBP = [0., 5., 35.] diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py index 7d1939a497..86d39ff885 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/selfdrive/car/subaru/subarucan.py @@ -13,6 +13,15 @@ def create_steering_control(packer, apply_steer, steer_req): return packer.make_can_msg("ES_LKAS", 0, values) +def create_steering_control_angle(packer, apply_steer, steer_req): + values = { + "LKAS_Output": apply_steer, + "LKAS_Request": steer_req, + "SET_3": 3 + } + return packer.make_can_msg("ES_LKAS_ANGLE", 0, values) + + def create_steering_status(packer): return packer.make_can_msg("ES_LKAS_State", 0, {}) @@ -46,9 +55,9 @@ def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long # Do not disable openpilot on Eyesight Soft Disable, if openpilot is controlling long values["Cruise_Soft_Disable"] = 0 + values["Cruise_Fault"] = 0 - if brake_cmd: - values["Cruise_Brake_Active"] = 1 + values["Cruise_Brake_Active"] = brake_cmd if pcm_cancel_cmd: values["Cruise_Cancel"] = 1 @@ -152,14 +161,15 @@ def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, l values["COUNTER"] = frame % 0x10 - if enabled and long_active: + if long_enabled: values["Cruise_State"] = 0 - values["Cruise_Activated"] = 1 + values["Cruise_Activated"] = enabled values["Cruise_Disengaged"] = 0 values["Car_Follow"] = int(lead_visible) - if long_enabled: values["PCB_Off"] = 1 # AEB is not presevered, so show the PCB_Off on dash + values["LDW_Off"] = 0 + values["Cruise_Fault"] = 0 # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts if values["LKAS_State_Msg"] in (2, 3): @@ -167,7 +177,7 @@ def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, l return packer.make_can_msg("ES_DashStatus", CanBus.main, values) -def create_es_brake(packer, frame, es_brake_msg, enabled, brake_value): +def create_es_brake(packer, frame, es_brake_msg, long_enabled, long_active, brake_value): values = {s: es_brake_msg[s] for s in [ "CHECKSUM", "Signal1", @@ -182,14 +192,14 @@ def create_es_brake(packer, frame, es_brake_msg, enabled, brake_value): values["COUNTER"] = frame % 0x10 - if enabled: - values["Cruise_Activated"] = 1 + if long_enabled: + values["Cruise_Brake_Fault"] = 0 + values["Cruise_Activated"] = long_active - values["Brake_Pressure"] = brake_value + values["Brake_Pressure"] = brake_value - if brake_value > 0: - values["Cruise_Brake_Active"] = 1 - values["Cruise_Brake_Lights"] = 1 if brake_value >= 70 else 0 + values["Cruise_Brake_Active"] = brake_value > 0 + values["Cruise_Brake_Lights"] = brake_value >= 70 return packer.make_can_msg("ES_Brake", CanBus.main, values) @@ -199,7 +209,6 @@ def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cr "Signal1", "Cruise_Fault", "Cruise_RPM", - "Signal2", "Cruise_Activated", "Brake_Lights", "Cruise_Hold", @@ -210,9 +219,9 @@ def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cr if long_enabled: values["Cruise_RPM"] = cruise_rpm + values["Cruise_Fault"] = 0 - if long_active: - values["Cruise_Activated"] = 1 + values["Cruise_Activated"] = long_active return packer.make_can_msg("ES_Status", CanBus.main, values) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 882d46b7c3..2f7350b966 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -93,6 +93,9 @@ class Footnote(Enum): GLOBAL = CarFootnote( "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", Column.PACKAGE) + EXP_LONG = CarFootnote( + "Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.", + Column.LONGITUDINAL) @dataclass @@ -104,6 +107,9 @@ class SubaruCarInfo(CarInfo): def init_make(self, CP: car.CarParams): self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) + if CP.experimentalLongitudinalAvailable: + self.footnotes.append(Footnote.EXP_LONG) + CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-21", "All"), CAR.OUTBACK: SubaruCarInfo("Subaru Outback 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b])), @@ -126,11 +132,20 @@ CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { CAR.LEGACY_PREGLOBAL: SubaruCarInfo("Subaru Legacy 2015-18"), CAR.OUTBACK_PREGLOBAL: SubaruCarInfo("Subaru Outback 2015-17"), CAR.OUTBACK_PREGLOBAL_2018: SubaruCarInfo("Subaru Outback 2018-19"), - CAR.FORESTER_2022: SubaruCarInfo("Subaru Forester 2022", "All", car_parts=CarParts.common([CarHarness.subaru_c])), + CAR.FORESTER_2022: SubaruCarInfo("Subaru Forester 2022-24", "All", car_parts=CarParts.common([CarHarness.subaru_c])), CAR.OUTBACK_2023: SubaruCarInfo("Subaru Outback 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d])), CAR.ASCENT_2023: SubaruCarInfo("Subaru Ascent 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d])), } +LKAS_ANGLE = {CAR.FORESTER_2022, CAR.OUTBACK_2023, CAR.ASCENT_2023} +GLOBAL_GEN2 = {CAR.OUTBACK, CAR.LEGACY, CAR.OUTBACK_2023, CAR.ASCENT_2023} +PREGLOBAL_CARS = {CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018} +HYBRID_CARS = {CAR.CROSSTREK_HYBRID, CAR.FORESTER_HYBRID} + +# Cars that temporarily fault when steering angle rate is greater than some threshold. +# Appears to be all torque-based cars produced around 2019 - present +STEER_RATE_LIMITED = GLOBAL_GEN2 | {CAR.IMPREZA_2020, CAR.FORESTER} + SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ @@ -141,573 +156,35 @@ FW_QUERY_CONFIG = FwQueryConfig( Request( [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], ), # Some Eyesight modules fail on TESTER_PRESENT_REQUEST # TODO: check if this resolves the fingerprinting issue for the 2023 Ascent and other new Subaru cars Request( [SUBARU_VERSION_REQUEST], [SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + ), + # Non-OBD requests + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + bus=0, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + bus=1, + obd_multiplexing=False, ), ], -) - -FW_VERSIONS = { - CAR.ASCENT: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 \x19\x02\x00', - b'\xa5 !\002\000', - b'\xf1\x82\xa5 \x19\x02\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x85\xc0\xd0\x00', - b'\005\xc0\xd0\000', - b'\x95\xc0\xd0\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00d\xb9\x1f@ \x10', - b'\000\000e~\037@ \'', - b'\x00\x00e@\x1f@ $', - b'\x00\x00d\xb9\x00\x00\x00\x00', - b'\x00\x00e@\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbb,\xa0t\a', - b'\xf1\x82\xbb,\xa0t\x87', - b'\xf1\x82\xbb,\xa0t\a', - b'\xf1\x82\xd9,\xa0@\a', - b'\xf1\x82\xd1,\xa0q\x07', - b'\xd1,\xa0q\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x00\xfe\xf7\x00\x00', - b'\001\xfe\xf9\000\000', - b'\x01\xfe\xf7\x00\x00', - b'\x01\xfe\xfa\x00\x00', - ], - }, - CAR.ASCENT_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 #\x03\x00', - ], - (Ecu.eps, 0x746, None): [ - b'%\xc0\xd0\x11', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x05!\x08\x1dK\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xe5,\xa0P\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\x04\xfe\xf3\x00\x00', - ], - }, - CAR.LEGACY: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1\\ x04\x01', - b'\xa1 \x03\x03', - b'\xa1 \x02\x01', - b'\xa1 \x02\x02', - ], - (Ecu.eps, 0x746, None): [ - b'\x9b\xc0\x11\x00', - b'\x9b\xc0\x11\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xde\"a0\x07', - b'\xe2"aq\x07', - b'\xde,\xa0@\x07', - b'\xe2,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6\x05@\x00', - b'\xa7\xf6\x04@\x00', - b'\xa5\xfe\xc7@\x00', - b'\xa7\xfe\xc4@\x00', - ], - }, - CAR.IMPREZA: { - (Ecu.abs, 0x7b0, None): [ - b'\x7a\x94\x3f\x90\x00', - b'\xa2 \x185\x00', - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'z\x94.\x90\x00', - b'z\x94\b\x90\x01', - b'\xa2 \x19`\x00', - b'z\x94\f\x90\001', - b'z\x9c\x19\x80\x01', - b'z\x94\x08\x90\x00', - b'z\x84\x19\x90\x00', - b'\xf1\x00\xb2\x06\x04', - b'z\x94\x0c\x90\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x7a\xc0\x0c\x00', - b'z\xc0\x08\x00', - b'\x8a\xc0\x00\x00', - b'z\xc0\x04\x00', - b'z\xc0\x00\x00', - b'\x8a\xc0\x10\x00', - b'z\xc0\n\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00\x64\xb5\x1f\x40\x20\x0e', - b'\x00\x00d\xdc\x1f@ \x0e', - b'\x00\x00e\x1c\x1f@ \x14', - b'\x00\x00d)\x1f@ \a', - b'\x00\x00e+\x1f@ \x14', - b'\000\000e+\000\000\000\000', - b'\000\000dd\037@ \016', - b'\000\000e\002\037@ \024', - b'\x00\x00d)\x00\x00\x00\x00', - b'\x00\x00c\xf4\x00\x00\x00\x00', - b'\x00\x00d\xdc\x00\x00\x00\x00', - b'\x00\x00dd\x00\x00\x00\x00', - b'\x00\x00c\xf4\x1f@ \x07', - b'\x00\x00e\x1c\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xaa\x61\x66\x73\x07', - b'\xbeacr\a', - b'\xc5!`r\a', - b'\xaa!ds\a', - b'\xaa!`u\a', - b'\xaa!dq\a', - b'\xaa!dt\a', - b'\xc5!ar\a', - b'\xbe!as\a', - b'\xc5!as\x07', - b'\xc5!ds\a', - b'\xc5!`s\a', - b'\xaa!au\a', - b'\xbe!at\a', - b'\xaa\x00Bu\x07', - b'\xc5!dr\x07', - b'\xaa!aw\x07', - b'\xaa!av\x07', - b'\xaa\x01bt\x07', - b'\xc5!ap\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe3\xe5\x46\x31\x00', - b'\xe4\xe5\x061\x00', - b'\xe5\xf5\x04\x00\x00', - b'\xe3\xf5G\x00\x00', - b'\xe3\xf5\a\x00\x00', - b'\xe3\xf5C\x00\x00', - b'\xe5\xf5B\x00\x00', - b'\xe5\xf5$\000\000', - b'\xe4\xf5\a\000\000', - b'\xe3\xf5F\000\000', - b'\xe4\xf5\002\000\000', - b'\xe3\xd0\x081\x00', - b'\xe3\xf5\x06\x00\x00', - b'\xe3\xd5\x161\x00', - ], - }, - CAR.IMPREZA_2020: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \0314\000', - b'\xa2 \0313\000', - b'\xa2 !i\000', - b'\xa2 !`\000', - b'\xf1\x00\xb2\x06\x04', - b'\xa2 `\x00', - b'\xa2 !3\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x9a\xc0\000\000', - b'\n\xc0\004\000', - b'\x9a\xc0\x04\x00', - b'\n\xc0\x04\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\000\000eb\037@ \"', - b'\x00\x00e\x8f\x1f@ )', - b'\x00\x00eq\x1f@ "', - b'\x00\x00eq\x00\x00\x00\x00', - b'\x00\x00e\x8f\x00\x00\x00\x00', - b'\x00\x00e\x92\x00\x00\x00\x00', - b'\x00\x00e\xa4\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xca!ap\a', - b'\xca!`p\a', - b'\xca!`0\a', - b'\xcc\"f0\a', - b'\xcc!fp\a', - b'\xcc!`p\x07', - b'\xca!f@\x07', - b'\xca!fp\x07', - b'\xf3"f@\x07', - b'\xe6!fp\x07', - b'\xf3"fp\x07', - b'\xe6"f0\x07', - b'\xe6"fp\x07', - b'\xe6!`@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe6\xf5\004\000\000', - b'\xe6\xf5$\000\000', - b'\xe7\xf5\x04\x00\x00', - b'\xe7\xf6B0\000', - b'\xe7\xf5D0\000', - b'\xf1\x00\xd7\x10@', - b'\xe6\xf5D0\x00', - b'\xe9\xf6F0\x00', - b'\xe9\xf5B0\x00', - b'\xe9\xf6B0\x00', - b'\xe9\xf5"\x00\x00', - ], - }, - CAR.CROSSTREK_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x19e\x01', - b'\xa2 !e\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x9a\xc2\x01\x00', - b'\n\xc2\x01\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00el\x1f@ #', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd7!`@\x07', - b'\xd7!`p\a', - b'\xf4!`0\x07', - ], - }, - CAR.FORESTER: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x18\x14\x00', - b'\xa3 \024\000', - b'\xa3 \031\024\000', - b'\xa3 \x14\x01', - b'\xf1\x00\xbb\r\x05', - b'\xa3 \x18&\x00', - b'\xa3 \x19&\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc0\x04\x00', - b'\x8d\xc0\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e!\x1f@ \x11', - b'\x00\x00e\x97\x1f@ 0', - b'\000\000e`\037@ ', - b'\xf1\x00\xac\x02\x00', - b'\x00\x00e!\x00\x00\x00\x00', - b'\x00\x00e\x97\x00\x00\x00\x00', - b'\x00\x00e^\x1f@ !', - b'\x00\x00e^\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb6"`A\x07', - b'\xcf"`0\x07', - b'\xcb\"`@\a', - b'\xcb\"`p\a', - b'\xf1\x00\xa2\x10\n', - b'\xcf"`p\x07', - b'\xb6\xa2`A\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\032\xf6B0\000', - b'\x1a\xf6F`\x00', - b'\032\xf6b`\000', - b'\x1a\xf6B`\x00', - b'\x1a\xf6b0\x00', - b'\x1a\xe6B1\x00', - b'\x1a\xe6F1\x00', - ], - }, - CAR.FORESTER_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x19T\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc2\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eY\x1f@ !', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd2\xa1`r\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1b\xa7@a\x00', - ], - }, - CAR.FORESTER_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'\x7d\x97\x14\x40', - b'\xf1\x00\xbb\x0c\x04', - b'm\x97\x14@', - ], - (Ecu.eps, 0x746, None): [ - b'}\xc0\x10\x00', - b'm\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00\x64\x35\x1f\x40\x20\x09', - b'\x00\x00c\xe9\x1f@ \x03', - b'\x00\x00d\xd3\x1f@ \t', - b'\x00\x00c\xe9\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xba"@p\a', - b'\xa7)\xa0q\a', - b'\xf1\x82\xa7)\xa0q\a', - b'\xba"@@\a', - b'\xa7"@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xdc\xf2\x60\x60\x00', - b'\xdc\xf2@`\x00', - b'\xda\xfd\xe0\x80\x00', - b'\xdc\xf2`\x81\000', - b'\xdc\xf2`\x80\x00', - b'\x1a\xf6F`\x00', - b'\xda\xf2`\x80\x00', - ], - }, - CAR.LEGACY_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'k\x97D\x00', - b'[\xba\xc4\x03', - b'{\x97D\x00', - b'[\x97D\000', - b'k\x9aD\x00', - ], - (Ecu.eps, 0x746, None): [ - b'[\xb0\x00\x01', - b'K\xb0\x00\x01', - b'k\xb0\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xab*@r\a', - b'\xa0+@p\x07', - b'\xb4"@0\x07', - b'\xa0"@q\a', - b'\xab+@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbe\xf2\x00p\x00', - b'\xbf\xfb\xc0\x80\x00', - b'\xbd\xf2\x00`\x00', - b'\xbf\xf2\000\x80\000', - b'\xbe\xfb\xc0p\x00', - ], - }, - CAR.OUTBACK_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'{\x9a\xac\x00', - b'k\x97\xac\x00', - b'\x5b\xf7\xbc\x03', - b'[\xf7\xac\x03', - b'{\x97\xac\x00', - b'k\x9a\xac\000', - b'[\xba\xac\x03', - b'[\xf7\xac\000', - ], - (Ecu.eps, 0x746, None): [ - b'k\xb0\x00\x00', - b'[\xb0\x00\x00', - b'\x4b\xb0\x00\x02', - b'K\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xec\x1f@ \x04', - b'\x00\x00c\xd1\x1f@\x10\x17', - b'\xf1\x00\xf0\xe0\x0e', - b'\x00\x00c\x94\x00\x00\x00\x00', - b'\x00\x00c\x94\x1f@\x10\b', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\000\000c\x90\037@\020\016', - b'\x00\x00c\xec\x37@\x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb4+@p\a', - b'\xab\"@@\a', - b'\xa0\x62\x41\x71\x07', - b'\xa0*@q\a', - b'\xab*@@\a', - b'\xb4"@0\a', - b'\xb4"@p\a', - b'\xab"@s\a', - b'\xab+@@\a', - b'\xb4"@r\a', - b'\xa0+@@\x07', - b'\xa0\"@\x80\a', - b'\xa0*@u\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xfb\xe0\x80\x00', - b'\xbe\xf2@\x80\x00', - b'\xbf\xe2\x40\x80\x00', - b'\xbf\xf2@\x80\x00', - b'\xbe\xf2@p\x00', - b'\xbd\xf2@`\x00', - b'\xbd\xf2@\x81\000', - b'\xbe\xfb\xe0p\000', - b'\xbf\xfb\xe0b\x00', - ], - }, - CAR.OUTBACK_PREGLOBAL_2018: { - (Ecu.abs, 0x7b0, None): [ - b'\x8b\x97\xac\x00', - b'\x8b\x9a\xac\x00', - b'\x9b\x97\xac\x00', - b'\x8b\x97\xbc\x00', - b'\x8b\x99\xac\x00', - b'\x9b\x9a\xac\000', - b'\x9b\x97\xbe\x10', - ], - (Ecu.eps, 0x746, None): [ - b'{\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00df\x1f@ \n', - b'\x00\x00d\xfe\x1f@ \x15', - b'\x00\x00d\x95\x00\x00\x00\x00', - b'\x00\x00d\x95\x1f@ \x0f', - b'\x00\x00d\xfe\x00\x00\x00\x00', - b'\x00\x00e\x19\x1f@ \x15', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb5"@p\a', - b'\xb5+@@\a', - b'\xb5"@P\a', - b'\xc4"@0\a', - b'\xb5b@1\x07', - b'\xb5q\xe0@\a', - b'\xc4+@0\a', - b'\xc4b@p\a', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbc\xf2@\x81\x00', - b'\xbc\xfb\xe0\x80\x00', - b'\xbc\xf2@\x80\x00', - b'\xbb\xf2@`\x00', - b'\xbc\xe2@\x80\x00', - b'\xbc\xfb\xe0`\x00', - b'\xbc\xaf\xe0`\x00', - b'\xbb\xfb\xe0`\000', - ], - }, - CAR.OUTBACK: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x06\x01', - b'\xa1 \a\x00', - b'\xa1 \b\001', - b'\xa1 \x06\x00', - b'\xa1 "\t\x01', - b'\xa1 \x08\x02', - b'\xa1 \x06\x02', - b'\xa1 \x07\x02', - b'\xa1 \x08\x00', - b'\xa1 "\t\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x9b\xc0\x10\x00', - b'\x9b\xc0\x20\x00', - b'\x1b\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eJ\x00\x1f@ \x19\x00', - b'\000\000e\x80\000\037@ \031\000', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - b'\x00\x00e\x9a\x00\x1f@ 1\x00', - b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbc,\xa0q\x07', - b'\xbc\"`@\a', - b'\xde"`0\a', - b'\xf1\x82\xbc,\xa0q\a', - b'\xf1\x82\xe3,\xa0@\x07', - b'\xe2"`0\x07', - b'\xe2"`p\x07', - b'\xf1\x82\xe2,\xa0@\x07', - b'\xbc"`q\x07', - b'\xe3,\xa0@\x07', - b'\xbc,\xa0u\x07', - b'\xde,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xfe\xf7@\x00', - b'\xa5\xf6D@\x00', - b'\xa5\xfe\xf6@\x00', - b'\xa7\x8e\xf40\x00', - b'\xf1\x82\xa7\xf6D@\x00', - b'\xa7\xf6D@\x00', - b'\xa7\xfe\xf4@\x00', - b'\xa5\xfe\xf8@\x00', - ], - }, - CAR.FORESTER_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 !x\x00', - b'\xa3 !v\x00', - b'\xa3 "v\x00', - b'\xa3 "x\x00', - ], - (Ecu.eps, 0x746, None): [ - b'-\xc0%0', - b'-\xc0\x040', - b'=\xc0%\x02', - b'=\xc04\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x04!\x01\x1eD\x07!\x00\x04,' - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd5"a0\x07', - b'\xd5"`0\x07', - b'\xf1"aq\x07', - b'\xf1"`q\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1d\x86B0\x00', - b'\x1d\xf6B0\x00', - b'\x1e\x86B0\x00', - b'\x1e\xf6D0\x00', - ], - }, - CAR.OUTBACK_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 #\x14\x00', - b'\xa1 #\x17\x00', - ], - (Ecu.eps, 0x746, None): [ - b'+\xc0\x10\x11\x00', - b'+\xc0\x12\x11\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\t!\x08\x046\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xed,\xa0q\x07', - b'\xed,\xa2q\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\xa8\x8e\xf41\x00', - b'\xa8\xfe\xf41\x00', - ] + # We don't get the EPS from non-OBD queries on GEN2 cars. Note that we still attempt to match when it exists + non_essential_ecus={ + Ecu.eps: list(GLOBAL_GEN2), } -} +) DBC = { CAR.ASCENT: dbc_dict('subaru_global_2017_generated', None), @@ -726,12 +203,3 @@ DBC = { CAR.OUTBACK_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), CAR.OUTBACK_PREGLOBAL_2018: dbc_dict('subaru_outback_2019_generated', None), } - -LKAS_ANGLE = {CAR.FORESTER_2022, CAR.OUTBACK_2023, CAR.ASCENT_2023} -GLOBAL_GEN2 = {CAR.OUTBACK, CAR.LEGACY, CAR.OUTBACK_2023, CAR.ASCENT_2023} -PREGLOBAL_CARS = {CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018} -HYBRID_CARS = {CAR.CROSSTREK_HYBRID, CAR.FORESTER_HYBRID} - -# Cars that temporarily fault when steering angle rate is greater than some threshold. -# Appears to be all torque-based cars produced around 2019 - present -STEER_RATE_LIMITED = GLOBAL_GEN2 | {CAR.IMPREZA_2020, CAR.FORESTER} diff --git a/selfdrive/car/tesla/fingerprints.py b/selfdrive/car/tesla/fingerprints.py new file mode 100644 index 0000000000..772ca59efa --- /dev/null +++ b/selfdrive/car/tesla/fingerprints.py @@ -0,0 +1,28 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.tesla.values import CAR + +Ecu = car.CarParams.Ecu + +FINGERPRINTS = { + CAR.AP1_MODELS: [{ + 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 267: 5, 277: 6, 280: 6, 283: 5, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 577: 8, 582: 5, 584: 4, 585: 8, 590: 8, 606: 8, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 660: 5, 693: 8, 696: 8, 697: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 809: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 841: 8, 845: 8, 846: 5, 852: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 873: 8, 877: 8, 878: 8, 879: 8, 880: 8, 884: 8, 888: 8, 889: 8, 893: 8, 896: 8, 901: 6, 904: 3, 905: 8, 908: 2, 909: 8, 920: 8, 921: 8, 925: 4, 936: 8, 937: 8, 941: 8, 949: 8, 952: 8, 953: 6, 957: 8, 968: 8, 973: 8, 984: 8, 987: 8, 989: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1016: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1064: 8, 1070: 8, 1080: 8, 1160: 4, 1281: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1368: 8, 1412: 8, 1436: 8, 1465: 8, 1476: 8, 1497: 8, 1524: 8, 1527: 8, 1601: 8, 1605: 8, 1611: 8, 1614: 8, 1617: 8, 1621: 8, 1627: 8, 1630: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2043: 5, 2045: 4 + }], +} + +FW_VERSIONS = { + CAR.AP2_MODELS: { + (Ecu.adas, 0x649, None): [ + b'\x01\x00\x8b\x07\x01\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x11', + ], + (Ecu.electricBrakeBooster, 0x64d, None): [ + b'1037123-00-A', + ], + (Ecu.fwdRadar, 0x671, None): [ + b'\x01\x00W\x00\x00\x00\x07\x00\x00\x00\x00\x08\x01\x00\x00\x00\x07\xff\xfe', + ], + (Ecu.eps, 0x730, None): [ + b'\x10#\x01', + ], + }, +} diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py index 548809af1b..12877f1344 100644 --- a/selfdrive/car/tesla/values.py +++ b/selfdrive/car/tesla/values.py @@ -1,4 +1,3 @@ -# ruff: noqa: E501 from collections import namedtuple from enum import StrEnum from typing import Dict, List, Union @@ -23,13 +22,6 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { CAR.AP2_MODELS: CarInfo("Tesla AP2 Model S", "All"), } -FINGERPRINTS = { - CAR.AP1_MODELS: [ - { - 1: 8, 3: 8, 14: 8, 21: 4, 69: 8, 109: 4, 257: 3, 264: 8, 267: 5, 277: 6, 280: 6, 283: 5, 293: 4, 296: 4, 309: 5, 325: 8, 328: 5, 336: 8, 341: 8, 360: 7, 373: 8, 389: 8, 415: 8, 513: 5, 516: 8, 520: 4, 522: 8, 524: 8, 526: 8, 532: 3, 536: 8, 537: 3, 542: 8, 551: 5, 552: 2, 556: 8, 558: 8, 568: 8, 569: 8, 574: 8, 577: 8, 582: 5, 584: 4, 585: 8, 590: 8, 606: 8, 622: 8, 627: 6, 638: 8, 641: 8, 643: 8, 660: 5, 693: 8, 696: 8, 697: 8, 712: 8, 728: 8, 744: 8, 760: 8, 772: 8, 775: 8, 776: 8, 777: 8, 778: 8, 782: 8, 788: 8, 791: 8, 792: 8, 796: 2, 797: 8, 798: 6, 799: 8, 804: 8, 805: 8, 807: 8, 808: 1, 809: 8, 812: 8, 813: 8, 814: 5, 815: 8, 820: 8, 823: 8, 824: 8, 829: 8, 830: 5, 836: 8, 840: 8, 841: 8, 845: 8, 846: 5, 852: 8, 856: 4, 857: 6, 861: 8, 862: 5, 872: 8, 873: 8, 877: 8, 878: 8, 879: 8, 880: 8, 884: 8, 888: 8, 889: 8, 893: 8, 896: 8, 901: 6, 904: 3, 905: 8, 908: 2, 909: 8, 920: 8, 921: 8, 925: 4, 936: 8, 937: 8, 941: 8, 949: 8, 952: 8, 953: 6, 957: 8, 968: 8, 973: 8, 984: 8, 987: 8, 989: 8, 990: 8, 1000: 8, 1001: 8, 1006: 8, 1016: 8, 1026: 8, 1028: 8, 1029: 8, 1030: 8, 1032: 1, 1033: 1, 1034: 8, 1048: 1, 1064: 8, 1070: 8, 1080: 8, 1160: 4, 1281: 8, 1329: 8, 1332: 8, 1335: 8, 1337: 8, 1368: 8, 1412: 8, 1436: 8, 1465: 8, 1476: 8, 1497: 8, 1524: 8, 1527: 8, 1601: 8, 1605: 8, 1611: 8, 1614: 8, 1617: 8, 1621: 8, 1627: 8, 1630: 8, 1800: 4, 1804: 8, 1812: 8, 1815: 8, 1816: 8, 1828: 8, 1831: 8, 1832: 8, 1840: 8, 1848: 8, 1864: 8, 1880: 8, 1892: 8, 1896: 8, 1912: 8, 1960: 8, 1992: 8, 2008: 3, 2043: 5, 2045: 4 - }, - ], -} DBC = { CAR.AP2_MODELS: dbc_dict('tesla_powertrain', 'tesla_radar', chassis_dbc='tesla_can'), @@ -55,22 +47,6 @@ FW_QUERY_CONFIG = FwQueryConfig( ] ) -FW_VERSIONS = { - CAR.AP2_MODELS: { - (Ecu.adas, 0x649, None): [ - b'\x01\x00\x8b\x07\x01\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x11', - ], - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00W\x00\x00\x00\x07\x00\x00\x00\x00\x08\x01\x00\x00\x00\x07\xff\xfe', - ], - (Ecu.eps, 0x730, None): [ - b'\x10#\x01', - ], - }, -} class CANBUS: # Lateral harness diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index a920bd45da..a454f616cb 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -14,6 +14,10 @@ from openpilot.selfdrive.car.car_helpers import interfaces from openpilot.selfdrive.car.fingerprints import all_known_cars from openpilot.selfdrive.car.fw_versions import FW_VERSIONS from openpilot.selfdrive.car.interfaces import get_interface_attr +from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle +from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID +from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque +from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.test.fuzzy_generation import DrawType, FuzzyGenerator ALL_ECUS = list({ecu for ecus in FW_VERSIONS.values() for ecu in ecus.keys()}) @@ -42,11 +46,6 @@ def get_fuzzy_car_interface_args(draw: DrawType) -> dict: class TestCarInterfaces(unittest.TestCase): - - @classmethod - def setUpClass(cls): - os.environ['NO_RADAR_SLEEP'] = '1' - # FIXME: Due to the lists used in carParams, Phase.target is very slow and will cause # many generated examples to overrun when max_examples > ~20, don't use it @parameterized.expand([(car,) for car in sorted(all_known_cars())]) @@ -75,6 +74,10 @@ class TestCarInterfaces(unittest.TestCase): self.assertEqual(len(car_params.longitudinalTuning.kiV), len(car_params.longitudinalTuning.kiBP)) self.assertEqual(len(car_params.longitudinalTuning.deadzoneV), len(car_params.longitudinalTuning.deadzoneBP)) + # If we're using the interceptor for gasPressed, we should be commanding gas with it + if car_params.enableGasInterceptor: + self.assertTrue(car_params.openpilotLongitudinalControl) + # Lateral sanity checks if car_params.steerControlType != car.CarParams.SteerControlType.angle: tune = car_params.lateralTuning @@ -105,6 +108,17 @@ class TestCarInterfaces(unittest.TestCase): car_interface.apply(CC, now_nanos) now_nanos += DT_CTRL * 1e9 # 10ms + # Test controller initialization + # TODO: wait until card refactor is merged to run controller a few times, + # hypothesis also slows down significantly with just one more message draw + LongControl(car_params) + if car_params.steerControlType == car.CarParams.SteerControlType.angle: + LatControlAngle(car_params, car_interface) + elif car_params.lateralTuning.which() == 'pid': + LatControlPID(car_params, car_interface) + elif car_params.lateralTuning.which() == 'torque': + LatControlTorque(car_params, car_interface) + # Test radar interface RadarInterface = importlib.import_module(f'selfdrive.car.{car_params.carName}.radar_interface').RadarInterface radar_interface = RadarInterface(car_params) diff --git a/selfdrive/car/torque_data/neural_ff_weights.json b/selfdrive/car/torque_data/neural_ff_weights.json new file mode 100644 index 0000000000..c526f07fa2 --- /dev/null +++ b/selfdrive/car/torque_data/neural_ff_weights.json @@ -0,0 +1 @@ +{"CHEVROLET BOLT EUV 2022": {"w_1": [[0.3452189564704895, -0.15614677965641022, -0.04062516987323761, -0.5960758328437805, 0.3211185932159424, 0.31732726097106934, -0.04430829733610153, -0.37327295541763306, -0.14118380844593048, 0.12712529301643372, 0.2641555070877075, -0.3451094627380371, -0.005127656273543835, 0.6185108423233032, 0.03725295141339302, 0.3763789236545563], [-0.0708412230014801, 0.3667356073856354, 0.031383827328681946, 0.1740853488445282, -0.04695861041545868, 0.018055908381938934, 0.009072160348296165, -0.23640218377113342, -0.10362917929887772, 0.022628149017691612, -0.224413201212883, 0.20718418061733246, -0.016947750002145767, -0.3872031271457672, -0.15500062704086304, -0.06375953555107117], [-0.0838046595454216, -0.0242826659232378, -0.07765661180019379, 0.028858814388513565, -0.09516210108995438, 0.008368706330657005, 0.1689300835132599, 0.015036891214549541, -0.15121428668498993, 0.1388195902109146, 0.11486363410949707, 0.0651545450091362, 0.13559958338737488, 0.04300367832183838, -0.13856294751167297, -0.058136988431215286], [-0.006249868310987949, 0.08809533715248108, -0.040690965950489044, 0.02359287068247795, -0.00766348373144865, 0.24816390872001648, -0.17360293865203857, -0.03676899895071983, -0.17564819753170013, 0.18998438119888306, -0.050583917647600174, -0.006488069426268339, 0.10649101436138153, -0.024557121098041534, -0.103276826441288, 0.18448011577129364]], "b_1": [0.2935388386249542, 0.10967712104320526, -0.014007942751049995, 0.211833655834198, 0.33605605363845825, 0.37722209095954895, -0.16615016758441925, 0.3134673535823822, 0.06695777177810669, 0.3425212800502777, 0.3769673705101013, 0.23186539113521576, 0.5770409107208252, -0.05929069593548775, 0.01839117519557476, 0.03828774020075798], "w_2": [[-0.06261160969734192, 0.010185074992477894, -0.06083013117313385, -0.04531499370932579, -0.08979734033346176, 0.3432150185108185, -0.019801849499344826, 0.3010321259498596], [0.19698476791381836, -0.009238275699317455, 0.08842222392559052, -0.09516377002000809, -0.05022778362035751, 0.13626104593276978, -0.052890390157699585, 0.15569131076335907], [0.0724768117070198, -0.09018408507108688, 0.06850195676088333, -0.025572121143341064, 0.0680626779794693, -0.07648195326328278, 0.07993496209383011, -0.059752143919467926], [1.267876386642456, -0.05755887180566788, -0.08429178595542908, 0.021366603672504425, -0.0006479775765910745, -1.4292563199996948, -0.08077696710824966, -1.414825439453125], [0.04535430669784546, 0.06555880606174469, -0.027145234867930412, -0.07661093026399612, -0.05702832341194153, 0.23650476336479187, 0.0024587824009358883, 0.20126521587371826], [0.006042032968252897, 0.042880818247795105, 0.002187949838116765, -0.017126334831118584, -0.08352015167474747, 0.19801731407642365, -0.029196614399552345, 0.23713473975658417], [-0.01644900068640709, -0.04358499124646187, 0.014584392309188843, 0.07155826687812805, -0.09354910999536514, -0.033351872116327286, 0.07138452678918839, -0.04755295440554619], [-1.1012420654296875, -0.03534531593322754, 0.02167935110628605, -0.01116552110761404, -0.08436500281095505, 1.1038788557052612, 0.027903547510504723, 1.0676132440567017], [0.03843916580080986, -0.0952216386795044, 0.039226632565259933, 0.002778085647150874, -0.020275786519050598, -0.07848760485649109, 0.04803166165947914, 0.015538203530013561], [0.018385495990514755, -0.025189843028783798, 0.0036680365446954966, -0.02105865254998207, 0.04808586835861206, 0.1575016975402832, 0.02703506126999855, 0.23039312660694122], [-0.0033881019335240126, -0.10210853815078735, -0.04877309128642082, 0.006989633198827505, 0.046798162162303925, 0.38676899671554565, -0.032304272055625916, 0.2345031052827835], [0.22092825174331665, -0.09642873704433441, 0.04499409720301628, 0.05108088254928589, -0.10191166400909424, 0.12818090617656708, -0.021021494641900063, 0.09440375864505768], [0.1212429478764534, -0.028194155544042587, -0.0981956496834755, 0.08226924389600754, 0.055346839129924774, 0.27067816257476807, -0.09064067900180817, 0.12580905854701996], [-1.6740131378173828, -0.02066155895590782, -0.05924689769744873, 0.06347910314798355, -0.07821853458881378, 1.2807466983795166, 0.04589352011680603, 1.310766577720642], [-0.09893272817134857, -0.04093599319458008, -0.02502273954451084, 0.09490344673395157, -0.0211324505507946, -0.09021010994911194, 0.07936318963766098, -0.03593116253614426], [-0.08490308374166489, -0.015558987855911255, -0.048692114651203156, -0.007421435788273811, -0.040531404316425323, 0.25889304280281067, 0.06012800335884094, 0.27946868538856506]], "b_2": [0.07973937690258026, -0.010446485131978989, -0.003066520905122161, -0.031895797699689865, 0.006032303906977177, 0.24106740951538086, -0.008969511836767197, 0.2872662842273712], "w_3": [[-1.364486813545227, -0.11682678014039993, 0.01764785870909691, 0.03926877677440643], [-0.05695437639951706, 0.05472218990325928, 0.1266128271818161, 0.09950875490903854], [0.11415273696184158, -0.10069356113672256, 0.0864749327301979, -0.043946366757154465], [-0.10138195008039474, -0.040128443390131, -0.08937158435583115, -0.0048376512713730335], [-0.0028251828625798225, -0.04743027314543724, 0.06340016424655914, 0.07277824729681015], [0.49482327699661255, -0.06410001963376999, -0.0999293103814125, -0.14250673353672028], [0.042802367359399796, 0.0015462725423276424, -0.05991362780332565, 0.1022040992975235], [0.3523194193840027, 0.07343732565641403, 0.04157765582203865, -0.12358107417821884]], "b_3": [0.2653026282787323, -0.058485131710767746, -0.0744510293006897, 0.012550175189971924], "w_4": [[0.5988775491714478, 0.09668736904859543], [-0.04360569268465042, 0.06491032242774963], [-0.11868984252214432, -0.09601487964391708], [-0.06554870307445526, -0.14189276099205017]], "b_4": [-0.08148707449436188, -2.8251802921295166], "input_norm_mat": [[-3.0, 3.0], [-3.0, 3.0], [0.0, 40.0], [-3.0, 3.0]], "output_norm_mat": [-1.0, 1.0], "temperature": 100.0}} \ No newline at end of file diff --git a/selfdrive/car/torque_data/override.toml b/selfdrive/car/torque_data/override.toml new file mode 100644 index 0000000000..339fc533e5 --- /dev/null +++ b/selfdrive/car/torque_data/override.toml @@ -0,0 +1,74 @@ +legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] +### angle control +# Nissan appears to have torque +"NISSAN X-TRAIL 2017" = [nan, 1.5, nan] +"NISSAN ALTIMA 2020" = [nan, 1.5, nan] +"NISSAN LEAF 2018 Instrument Cluster" = [nan, 1.5, nan] +"NISSAN LEAF 2018" = [nan, 1.5, nan] +"NISSAN ROGUE 2019" = [nan, 1.5, nan] + +# New subarus angle based controllers +"SUBARU FORESTER 2022" = [nan, 3.0, nan] +"SUBARU OUTBACK 7TH GEN" = [nan, 3.0, nan] +"SUBARU ASCENT 2023" = [nan, 3.0, nan] + +# Toyota LTA also has torque +"TOYOTA RAV4 2023" = [nan, 3.0, nan] + +# Tesla has high torque +"TESLA AP1 MODEL S" = [nan, 2.5, nan] +"TESLA AP2 MODEL S" = [nan, 2.5, nan] + +# Guess +"FORD BRONCO SPORT 1ST GEN" = [nan, 1.5, nan] +"FORD ESCAPE 4TH GEN" = [nan, 1.5, nan] +"FORD EXPLORER 6TH GEN" = [nan, 1.5, nan] +"FORD F-150 14TH GEN" = [nan, 1.5, nan] +"FORD FOCUS 4TH GEN" = [nan, 1.5, nan] +"FORD MAVERICK 1ST GEN" = [nan, 1.5, nan] +"FORD F-150 LIGHTNING 1ST GEN" = [nan, 1.5, nan] +"FORD MUSTANG MACH-E 1ST GEN" = [nan, 1.5, nan] +### + +# No steering wheel +"COMMA BODY" = [nan, 1000, nan] + +# Totally new cars +"RAM 1500 5TH GEN" = [2.0, 2.0, 0.05] +"RAM HD 5TH GEN" = [1.4, 1.4, 0.05] +"SUBARU OUTBACK 6TH GEN" = [2.0, 2.0, 0.2] +"CADILLAC ESCALADE 2017" = [1.899999976158142, 1.842270016670227, 0.1120000034570694] +"CADILLAC ESCALADE ESV 2019" = [1.15, 1.3, 0.2] +"CHEVROLET BOLT EUV 2022" = [2.0, 2.0, 0.05] +"CHEVROLET SILVERADO 1500 2020" = [1.9, 1.9, 0.112] +"CHEVROLET TRAILBLAZER 2021" = [1.33, 1.9, 0.16] +"CHEVROLET EQUINOX 2019" = [2.5, 2.5, 0.05] +"VOLKSWAGEN PASSAT NMS" = [2.5, 2.5, 0.1] +"VOLKSWAGEN SHARAN 2ND GEN" = [2.5, 2.5, 0.1] +"HYUNDAI SANTA CRUZ 1ST GEN" = [2.7, 2.7, 0.1] +"KIA SPORTAGE 5TH GEN" = [2.6, 2.6, 0.1] +"GENESIS GV70 1ST GEN" = [2.42, 2.42, 0.1] +"GENESIS GV60 ELECTRIC 1ST GEN" = [2.5, 2.5, 0.1] +"KIA SORENTO 4TH GEN" = [2.5, 2.5, 0.1] +"KIA SORENTO HYBRID 4TH GEN" = [2.5, 2.5, 0.1] +"KIA NIRO HYBRID 2ND GEN" = [2.42, 2.5, 0.12] +"KIA NIRO EV 2ND GEN" = [2.05, 2.5, 0.14] +"GENESIS GV80 2023" = [2.5, 2.5, 0.1] +"KIA CARNIVAL 4TH GEN" = [1.75, 1.75, 0.15] +"GMC ACADIA DENALI 2018" = [1.6, 1.6, 0.2] +"LEXUS IS 2023" = [2.0, 2.0, 0.1] +"HYUNDAI KONA ELECTRIC 2ND GEN" = [2.5, 2.5, 0.1] +"HYUNDAI IONIQ 6 2023" = [2.5, 2.5, 0.1] +"HYUNDAI AZERA 6TH GEN" = [1.8, 1.8, 0.1] +"HYUNDAI AZERA HYBRID 6TH GEN" = [1.8, 1.8, 0.1] +"KIA K8 HYBRID 1ST GEN" = [2.5, 2.5, 0.1] +"HYUNDAI CUSTIN 1ST GEN" = [2.5, 2.5, 0.1] +"LEXUS GS F 2016" = [2.5, 2.5, 0.08] +"HYUNDAI STARIA 4TH GEN" = [1.8, 2.0, 0.15] + +# Dashcam or fallback configured as ideal car +"mock" = [10.0, 10, 0.0] + +# Manually checked +"HONDA CIVIC 2022" = [2.5, 1.2, 0.15] +"HONDA HR-V 2023" = [2.5, 1.2, 0.2] diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml deleted file mode 100644 index 12b483cfa7..0000000000 --- a/selfdrive/car/torque_data/override.yaml +++ /dev/null @@ -1,73 +0,0 @@ -legend: [LAT_ACCEL_FACTOR, MAX_LAT_ACCEL_MEASURED, FRICTION] -### angle control -# Nissan appears to have torque -NISSAN X-TRAIL 2017: [.nan, 1.5, .nan] -NISSAN ALTIMA 2020: [.nan, 1.5, .nan] -NISSAN LEAF 2018 Instrument Cluster: [.nan, 1.5, .nan] -NISSAN LEAF 2018: [.nan, 1.5, .nan] -NISSAN ROGUE 2019: [.nan, 1.5, .nan] - -# New subarus angle based controllers -SUBARU FORESTER 2022: [.nan, 3.0, .nan] -SUBARU OUTBACK 7TH GEN: [.nan, 3.0, .nan] -SUBARU ASCENT 2023: [.nan, 3.0, .nan] - -# Toyota LTA also has torque -TOYOTA RAV4 2023: [.nan, 3.0, .nan] - -# Tesla has high torque -TESLA AP1 MODEL S: [.nan, 2.5, .nan] -TESLA AP2 MODEL S: [.nan, 2.5, .nan] - -# Guess -FORD BRONCO SPORT 1ST GEN: [.nan, 1.5, .nan] -FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan] -FORD EXPLORER 6TH GEN: [.nan, 1.5, .nan] -FORD F-150 14TH GEN: [.nan, 1.5, .nan] -FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] -FORD MAVERICK 1ST GEN: [.nan, 1.5, .nan] -### - -# No steering wheel -COMMA BODY: [.nan, 1000, .nan] - -# Totally new cars -RAM 1500 5TH GEN: [2.0, 2.0, 0.05] -RAM HD 5TH GEN: [1.4, 1.4, 0.05] -SUBARU OUTBACK 6TH GEN: [2.0, 2.0, 0.2] -CADILLAC ESCALADE 2017: [1.899999976158142, 1.842270016670227, 0.1120000034570694] -CADILLAC ESCALADE ESV 2019: [1.15, 1.3, 0.2] -CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] -CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] -CHEVROLET TRAILBLAZER 2021: [1.33, 1.9, 0.16] -CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05] -VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] -VOLKSWAGEN SHARAN 2ND GEN: [2.5, 2.5, 0.1] -HYUNDAI SANTA CRUZ 1ST GEN: [2.7, 2.7, 0.1] -KIA SPORTAGE 5TH GEN: [2.7, 2.7, 0.1] -KIA SPORTAGE HYBRID 5TH GEN: [2.5, 2.5, 0.1] -GENESIS GV70 1ST GEN: [2.42, 2.42, 0.1] -KIA SORENTO PLUG-IN HYBRID 4TH GEN: [2.5, 2.5, 0.1] -GENESIS GV60 ELECTRIC 1ST GEN: [2.5, 2.5, 0.1] -KIA SORENTO 4TH GEN: [2.5, 2.5, 0.1] -KIA NIRO HYBRID 2ND GEN: [2.42, 2.5, 0.12] -KIA NIRO EV 2ND GEN: [2.05, 2.5, 0.14] -GENESIS GV80 2023: [2.5, 2.5, 0.1] -KIA CARNIVAL 4TH GEN: [1.75, 1.75, 0.15] -GMC ACADIA DENALI 2018: [1.6, 1.6, 0.2] -LEXUS IS 2023: [2.0, 2.0, 0.1] -KIA SORENTO HYBRID 4TH GEN: [2.5, 2.5, 0.1] -HYUNDAI KONA ELECTRIC 2ND GEN: [2.5, 2.5, 0.1] -HYUNDAI IONIQ 6 2023: [2.5, 2.5, 0.1] -HYUNDAI AZERA 6TH GEN: [1.8, 1.8, 0.1] -HYUNDAI AZERA HYBRID 6TH GEN: [1.8, 1.8, 0.1] -KIA K8 HYBRID 1ST GEN: [2.5, 2.5, 0.1] -HYUNDAI CUSTIN 1ST GEN: [2.5, 2.5, 0.1] -LEXUS GS F 2016: [2.5, 2.5, 0.08] - -# Dashcam or fallback configured as ideal car -mock: [10.0, 10, 0.0] - -# Manually checked -HONDA CIVIC 2022: [2.5, 1.2, 0.15] -HONDA HR-V 2023: [2.5, 1.2, 0.2] diff --git a/selfdrive/car/torque_data/params.toml b/selfdrive/car/torque_data/params.toml new file mode 100644 index 0000000000..568646c84c --- /dev/null +++ b/selfdrive/car/torque_data/params.toml @@ -0,0 +1,86 @@ +legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] +"ACURA ILX 2016" = [1.524988973896102, 0.519011053086259, 0.34236219253028] +"ACURA RDX 2018" = [0.9987728568686902, 0.5323765166196301, 0.303218805715844] +"ACURA RDX 2020" = [1.4314459806646749, 0.33874701282109954, 0.18048847083897598] +"AUDI A3 3RD GEN" = [1.5122414863077502, 1.7443517531719404, 0.15194151892450905] +"AUDI Q3 2ND GEN" = [1.4439223359448605, 1.2254955789112076, 0.1413798895978097] +"CHEVROLET VOLT PREMIER 2017" = [1.5961527626411784, 1.8422651988094612, 0.1572393918005158] +"CHRYSLER PACIFICA 2018" = [2.07140, 1.3366521181047952, 0.13776367250652022] +"CHRYSLER PACIFICA 2020" = [1.86206, 1.509076559398423, 0.14328246159386085] +"CHRYSLER PACIFICA HYBRID 2017" = [1.79422, 1.06831764583744, 0.116237] +"CHRYSLER PACIFICA HYBRID 2018" = [2.08887, 1.2943025830995154, 0.114818] +"CHRYSLER PACIFICA HYBRID 2019" = [1.90120, 1.1958788168371808, 0.131520] +"GENESIS G70 2018" = [3.8520195946707947, 2.354697063349854, 0.06830285485626221] +"HONDA ACCORD 2018" = [1.7135052593468778, 0.3461280068322071, 0.21579936052863807] +"HONDA ACCORD HYBRID 2018" = [1.6651615004829625, 0.30322180951193245, 0.2083000440586149] +"HONDA CIVIC (BOSCH) 2019" = [1.691708637466905, 0.40132900729454185, 0.25460295304024094] +"HONDA CIVIC 2016" = [1.6528895627785531, 0.4018518740819229, 0.25458812851328544] +"HONDA CR-V 2016" = [0.7667141440182675, 0.5927571534745969, 0.40909087636157127] +"HONDA CR-V 2017" = [2.01323205142022, 0.2700612209345081, 0.2238412881331528] +"HONDA CR-V HYBRID 2019" = [2.072034634644233, 0.7152085160516978, 0.20237105008376083] +"HONDA FIT 2018" = [1.5719981427109775, 0.5712761407108976, 0.110773383324281] +"HONDA HRV 2019" = [2.0661212805710205, 0.7521343418694775, 0.17760375789242094] +"HONDA INSIGHT 2019" = [1.5201671214069354, 0.5660229120683284, 0.25808042580281876] +"HONDA ODYSSEY 2018" = [1.8774809275211801, 0.8394431662987996, 0.2096978613792822] +"HONDA PILOT 2017" = [1.7262026201812795, 0.9470005614967523, 0.21351430733218763] +"HONDA RIDGELINE 2017" = [1.4146525028237624, 0.7356572861629564, 0.23307177552211328] +"HYUNDAI ELANTRA 2021" = [3.169, 2.1259108157250735, 0.0819] +"HYUNDAI GENESIS 2015-2016" = [2.7807965280270794, 2.325, 0.0984484465421171] +"HYUNDAI IONIQ 5 2022" = [3.172929, 2.713050, 0.096019] +"HYUNDAI IONIQ ELECTRIC LIMITED 2019" = [1.7662975472852054, 1.613755614526594, 0.17087579756306276] +"HYUNDAI IONIQ PHEV 2020" = [3.2928700076638537, 2.1193482926455656, 0.12463700961468778] +"HYUNDAI IONIQ PLUG-IN HYBRID 2019" = [2.970807902012267, 1.6312321830002083, 0.1088964990357482] +"HYUNDAI KONA ELECTRIC 2019" = [3.078814714619148, 2.307336938253934, 0.12359762054065548] +"HYUNDAI PALISADE 2020" = [2.544642494803999, 1.8721703683337008, 0.1301424599248651] +"HYUNDAI SANTA FE 2019" = [3.0787027729757632, 2.6173437483495565, 0.1207019341823945] +"HYUNDAI SANTA FE HYBRID 2022" = [3.501877602644835, 2.729064118456137, 0.10384068104538963] +"HYUNDAI SANTA FE PlUG-IN HYBRID 2022" = [1.6953050513611045, 1.5837614296206861, 0.12672855941458458] +"HYUNDAI SONATA 2019" = [2.2200457811703953, 1.2967330275895228, 0.14039920986586393] +"HYUNDAI SONATA 2020" = [2.9638737459977467, 2.1259108157250735, 0.07813665616927593] +"HYUNDAI SONATA HYBRID 2021" = [2.8990264092395734, 2.061410192222139, 0.0899805488717382] +"HYUNDAI TUCSON 4TH GEN" = [2.960174, 2.860284, 0.108745] +"JEEP GRAND CHEROKEE 2019" = [2.30972, 1.289689569171081, 0.117048] +"JEEP GRAND CHEROKEE V6 2018" = [2.27116, 1.4057367824262523, 0.11725947414922003] +"KIA EV6 2022" = [3.2, 2.093457, 0.05] +"KIA K5 2021" = [2.405339728085138, 1.460032270828705, 0.11650989850813716] +"KIA NIRO EV 2020" = [2.9215954981365337, 2.1500583840260044, 0.09236802474810267] +"KIA SORENTO GT LINE 2018" = [2.464854685101844, 1.5335274218367956, 0.12056170567599558] +"KIA STINGER GT2 2018" = [2.7499043387418967, 1.849652021986449, 0.12048334239559202] +"LEXUS ES 2019" = [2.0357564999999997, 1.999082295195227, 0.101533] +"LEXUS NX 2018" = [2.3525924753753613, 1.9731412277641067, 0.15168101064205927] +"LEXUS NX 2020" = [2.4331999786982936, 2.1045680431705414, 0.14099899317761067] +"LEXUS RX 2016" = [1.6430539050086406, 1.181960058934143, 0.19768806040843034] +"LEXUS RX 2020" = [1.5375561442049257, 1.343166476215164, 0.1931062001527557] +"MAZDA CX-9 2021" = [1.7601682915983443, 1.0889677335154337, 0.17713792194297195] +"SKODA SUPERB 3RD GEN" = [1.166437404652981, 1.1686163012668165, 0.12194533036948708] +"SUBARU FORESTER 2019" = [3.6617001649776793, 2.342197172531713, 0.11075960785398745] +"SUBARU IMPREZA LIMITED 2019" = [1.0670704910352047, 0.8234374840709592, 0.20986563268614938] +"SUBARU IMPREZA SPORT 2020" = [2.6068223389108303, 2.134872342760203, 0.15261513193561627] +"TOYOTA AVALON 2016" = [2.5185770183845646, 1.7153346784214922, 0.10603968787111022] +"TOYOTA AVALON 2019" = [1.7036141952825095, 1.239619084240008, 0.08459830394899492] +"TOYOTA AVALON 2022" = [2.3154403649717357, 2.7777922854327124, 0.11453999639164605] +"TOYOTA C-HR 2018" = [1.5591084333664578, 1.271271459066948, 0.20259087058453193] +"TOYOTA C-HR 2021" = [1.7678810166088303, 1.3742176337919942, 0.2319674583741509] +"TOYOTA CAMRY 2018" = [2.0568162685952505, 1.7576185169559122, 0.108878753] +"TOYOTA CAMRY 2021" = [2.3548324999999997, 2.368900128946771, 0.118436] +"TOYOTA COROLLA 2017" = [3.117154369115421, 1.8438132575043773, 0.12289685869250652] +"TOYOTA COROLLA TSS2 2019" = [1.991132339206426, 1.868866242720403, 0.19570063298031432] +"TOYOTA HIGHLANDER 2017" = [1.8108348718624456, 1.6348421600679828, 0.15972686105120398] +"TOYOTA HIGHLANDER 2020" = [1.9617570834136164, 1.8611643317268927, 0.14519673256119725] +"TOYOTA MIRAI 2021" = [2.506899832157829, 1.7417213930750164, 0.20182618449440565] +"TOYOTA PRIUS 2017" = [1.60, 1.5023147650693636, 0.151515] +"TOYOTA PRIUS TSS2 2021" = [1.972600, 1.9104337425537743, 0.170968] +"TOYOTA RAV4 2017" = [2.085695074355425, 2.2142832316984733, 0.13339165270103975] +"TOYOTA RAV4 2019" = [2.279239424615458, 2.087101966779332, 0.13682208413446817] +"TOYOTA RAV4 2019 8965" = [2.3080951748210854, 2.1189367835820603, 0.12942102328134028] +"TOYOTA RAV4 2019 x02" = [2.762293266024922, 2.243615865975329, 0.11113568178327986] +"TOYOTA RAV4 HYBRID 2017" = [1.9796257271652042, 1.7503987331707576, 0.14628860048885406] +"TOYOTA RAV4 2022" = [2.241883248393209, 1.9304407208090029, 0.112174] +"TOYOTA RAV4 2022 x02" = [3.044930631831037, 2.3979189796380918, 0.14023209146703736] +"TOYOTA SIENNA 2018" = [1.689726, 1.3208264576110418, 0.140456] +"VOLKSWAGEN ARTEON 1ST GEN" = [1.45136518053819, 1.3639364049316804, 0.23806361745695032] +"VOLKSWAGEN ATLAS 1ST GEN" = [1.4677006726964945, 1.6733266634075656, 0.12959584092073367] +"VOLKSWAGEN GOLF 7TH GEN" = [1.3750394140491293, 1.5814743077200641, 0.2018321939386586] +"VOLKSWAGEN JETTA 7TH GEN" = [1.2271623034089392, 1.216955117387, 0.19437384688370712] +"VOLKSWAGEN PASSAT 8TH GEN" = [1.3432120736752917, 1.7087275587362314, 0.19444383787326647] +"VOLKSWAGEN TIGUAN 2ND GEN" = [0.9711965500094828, 1.0001565939459098, 0.1465626137072916] diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml deleted file mode 100644 index 2d2dbc3f0b..0000000000 --- a/selfdrive/car/torque_data/params.yaml +++ /dev/null @@ -1,88 +0,0 @@ -ACURA ILX 2016: [1.524988973896102, 0.519011053086259, 0.34236219253028] -ACURA RDX 2018: [0.9987728568686902, 0.5323765166196301, 0.303218805715844] -ACURA RDX 2020: [1.4314459806646749, 0.33874701282109954, 0.18048847083897598] -AUDI A3 3RD GEN: [1.5122414863077502, 1.7443517531719404, 0.15194151892450905] -AUDI Q3 2ND GEN: [1.4439223359448605, 1.2254955789112076, 0.1413798895978097] -CHEVROLET VOLT PREMIER 2017: [1.5961527626411784, 1.8422651988094612, 0.1572393918005158] -CHRYSLER PACIFICA 2018: [2.07140, 1.3366521181047952, 0.13776367250652022] -CHRYSLER PACIFICA 2020: [1.86206, 1.509076559398423, 0.14328246159386085] -CHRYSLER PACIFICA HYBRID 2017: [1.79422, 1.06831764583744, 0.116237] -CHRYSLER PACIFICA HYBRID 2018: [2.08887, 1.2943025830995154, 0.114818] -CHRYSLER PACIFICA HYBRID 2019: [1.90120, 1.1958788168371808, 0.131520] -GENESIS G70 2018: [3.8520195946707947, 2.354697063349854, 0.06830285485626221] -HONDA ACCORD 2018: [1.7135052593468778, 0.3461280068322071, 0.21579936052863807] -HONDA ACCORD HYBRID 2018: [1.6651615004829625, 0.30322180951193245, 0.2083000440586149] -HONDA CIVIC (BOSCH) 2019: [1.691708637466905, 0.40132900729454185, 0.25460295304024094] -HONDA CIVIC 2016: [1.6528895627785531, 0.4018518740819229, 0.25458812851328544] -HONDA CR-V 2016: [0.7667141440182675, 0.5927571534745969, 0.40909087636157127] -HONDA CR-V 2017: [2.01323205142022, 0.2700612209345081, 0.2238412881331528] -HONDA CR-V HYBRID 2019: [2.072034634644233, 0.7152085160516978, 0.20237105008376083] -HONDA FIT 2018: [1.5719981427109775, 0.5712761407108976, 0.110773383324281] -HONDA HRV 2019: [2.0661212805710205, 0.7521343418694775, 0.17760375789242094] -HONDA INSIGHT 2019: [1.5201671214069354, 0.5660229120683284, 0.25808042580281876] -HONDA ODYSSEY 2018: [1.8774809275211801, 0.8394431662987996, 0.2096978613792822] -HONDA PILOT 2017: [1.7262026201812795, 0.9470005614967523, 0.21351430733218763] -HONDA RIDGELINE 2017: [1.4146525028237624, 0.7356572861629564, 0.23307177552211328] -HYUNDAI ELANTRA 2021: [3.169, 2.1259108157250735, 0.0819] -HYUNDAI GENESIS 2015-2016: [2.7807965280270794, 2.325, 0.0984484465421171] -HYUNDAI IONIQ 5 2022: [3.172929, 2.713050, 0.096019] -HYUNDAI IONIQ ELECTRIC LIMITED 2019: [1.7662975472852054, 1.613755614526594, 0.17087579756306276] -HYUNDAI IONIQ PHEV 2020: [3.2928700076638537, 2.1193482926455656, 0.12463700961468778] -HYUNDAI IONIQ PLUG-IN HYBRID 2019: [2.970807902012267, 1.6312321830002083, 0.1088964990357482] -HYUNDAI KONA ELECTRIC 2019: [3.078814714619148, 2.307336938253934, 0.12359762054065548] -HYUNDAI PALISADE 2020: [2.544642494803999, 1.8721703683337008, 0.1301424599248651] -HYUNDAI SANTA FE 2019: [3.0787027729757632, 2.6173437483495565, 0.1207019341823945] -HYUNDAI SANTA FE HYBRID 2022: [3.501877602644835, 2.729064118456137, 0.10384068104538963] -HYUNDAI SANTA FE PlUG-IN HYBRID 2022: [1.6953050513611045, 1.5837614296206861, 0.12672855941458458] -HYUNDAI SONATA 2019: [2.2200457811703953, 1.2967330275895228, 0.14039920986586393] -HYUNDAI SONATA 2020: [2.9638737459977467, 2.1259108157250735, 0.07813665616927593] -HYUNDAI SONATA HYBRID 2021: [2.8990264092395734, 2.061410192222139, 0.0899805488717382] -HYUNDAI TUCSON HYBRID 4TH GEN: [2.035545, 2.035545, 0.110272] -JEEP GRAND CHEROKEE 2019: [2.30972, 1.289689569171081, 0.117048] -JEEP GRAND CHEROKEE V6 2018: [2.27116, 1.4057367824262523, 0.11725947414922003] -KIA EV6 2022: [3.2, 2.093457, 0.05] -KIA K5 2021: [2.405339728085138, 1.460032270828705, 0.11650989850813716] -KIA NIRO EV 2020: [2.9215954981365337, 2.1500583840260044, 0.09236802474810267] -KIA SORENTO GT LINE 2018: [2.464854685101844, 1.5335274218367956, 0.12056170567599558] -KIA STINGER GT2 2018: [2.7499043387418967, 1.849652021986449, 0.12048334239559202] -LEXUS ES 2019: [2.0357564999999997, 1.999082295195227, 0.101533] -LEXUS NX 2018: [2.3525924753753613, 1.9731412277641067, 0.15168101064205927] -LEXUS NX 2020: [2.4331999786982936, 2.1045680431705414, 0.14099899317761067] -LEXUS RX 2016: [1.5876816543130423, 1.0427699298523752, 0.21334066732397142] -LEXUS RX 2020: [1.5375561442049257, 1.343166476215164, 0.1931062001527557] -LEXUS RX HYBRID 2017: [1.6984261557042386, 1.3211501880159107, 0.1820354534928893] -MAZDA CX-9 2021: [1.7601682915983443, 1.0889677335154337, 0.17713792194297195] -SKODA SUPERB 3RD GEN: [1.166437404652981, 1.1686163012668165, 0.12194533036948708] -SUBARU FORESTER 2019: [3.6617001649776793, 2.342197172531713, 0.11075960785398745] -SUBARU IMPREZA LIMITED 2019: [1.0670704910352047, 0.8234374840709592, 0.20986563268614938] -SUBARU IMPREZA SPORT 2020: [2.6068223389108303, 2.134872342760203, 0.15261513193561627] -TOYOTA AVALON 2016: [2.5185770183845646, 1.7153346784214922, 0.10603968787111022] -TOYOTA AVALON 2019: [1.7036141952825095, 1.239619084240008, 0.08459830394899492] -TOYOTA AVALON 2022: [2.3154403649717357, 2.7777922854327124, 0.11453999639164605] -TOYOTA C-HR 2018: [1.5591084333664578, 1.271271459066948, 0.20259087058453193] -TOYOTA C-HR 2021: [1.7678810166088303, 1.3742176337919942, 0.2319674583741509] -TOYOTA CAMRY 2018: [2.0568162685952505, 1.7576185169559122, 0.108878753] -TOYOTA CAMRY 2021: [2.3548324999999997, 2.368900128946771, 0.118436] -TOYOTA COROLLA 2017: [3.117154369115421, 1.8438132575043773, 0.12289685869250652] -TOYOTA COROLLA TSS2 2019: [1.991132339206426, 1.868866242720403, 0.19570063298031432] -TOYOTA HIGHLANDER 2017: [1.8696367437248915, 1.626293990451463, 0.17485372210240796] -TOYOTA HIGHLANDER 2020: [1.9617570834136164, 1.8611643317268927, 0.14519673256119725] -TOYOTA HIGHLANDER HYBRID 2018: [1.752033, 1.6433903296845025, 0.144600] -TOYOTA MIRAI 2021: [2.506899832157829, 1.7417213930750164, 0.20182618449440565] -TOYOTA PRIUS 2017: [1.60, 1.5023147650693636, 0.151515] -TOYOTA PRIUS TSS2 2021: [1.972600, 1.9104337425537743, 0.170968] -TOYOTA RAV4 2017: [2.085695074355425, 2.2142832316984733, 0.13339165270103975] -TOYOTA RAV4 2019: [2.279239424615458, 2.087101966779332, 0.13682208413446817] -TOYOTA RAV4 2019 8965: [2.3080951748210854, 2.1189367835820603, 0.12942102328134028] -TOYOTA RAV4 2019 x02: [2.762293266024922, 2.243615865975329, 0.11113568178327986] -TOYOTA RAV4 HYBRID 2017: [1.9796257271652042, 1.7503987331707576, 0.14628860048885406] -TOYOTA RAV4 2022: [2.241883248393209, 1.9304407208090029, 0.112174] -TOYOTA RAV4 2022 x02: [3.044930631831037, 2.3979189796380918, 0.14023209146703736] -TOYOTA SIENNA 2018: [1.689726, 1.3208264576110418, 0.140456] -VOLKSWAGEN ARTEON 1ST GEN: [1.45136518053819, 1.3639364049316804, 0.23806361745695032] -VOLKSWAGEN ATLAS 1ST GEN: [1.4677006726964945, 1.6733266634075656, 0.12959584092073367] -VOLKSWAGEN GOLF 7TH GEN: [1.3750394140491293, 1.5814743077200641, 0.2018321939386586] -VOLKSWAGEN JETTA 7TH GEN: [1.2271623034089392, 1.216955117387, 0.19437384688370712] -VOLKSWAGEN PASSAT 8TH GEN: [1.3432120736752917, 1.7087275587362314, 0.19444383787326647] -VOLKSWAGEN TIGUAN 2ND GEN: [0.9711965500094828, 1.0001565939459098, 0.1465626137072916] -legend: [LAT_ACCEL_FACTOR, MAX_LAT_ACCEL_MEASURED, FRICTION] diff --git a/selfdrive/car/torque_data/substitute.toml b/selfdrive/car/torque_data/substitute.toml new file mode 100644 index 0000000000..6822ef437b --- /dev/null +++ b/selfdrive/car/torque_data/substitute.toml @@ -0,0 +1,85 @@ +legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] +"MAZDA 3" = "MAZDA CX-9 2021" +"MAZDA 6" = "MAZDA CX-9 2021" +"MAZDA CX-5" = "MAZDA CX-9 2021" +"MAZDA CX-5 2022" = "MAZDA CX-9 2021" +"MAZDA CX-9" = "MAZDA CX-9 2021" + +"DODGE DURANGO 2021" = "CHRYSLER PACIFICA 2020" + +"TOYOTA ALPHARD 2020" = "TOYOTA SIENNA 2018" +"TOYOTA PRIUS v 2017" = "TOYOTA PRIUS 2017" +"LEXUS IS 2018" = "LEXUS NX 2018" +"LEXUS CT HYBRID 2018" = "LEXUS NX 2018" +"LEXUS ES 2018" = "TOYOTA CAMRY 2018" +"LEXUS RC 2020" = "LEXUS NX 2020" +"LEXUS LC 2024" = "LEXUS NX 2020" + +"KIA OPTIMA 4TH GEN" = "HYUNDAI SONATA 2020" +"KIA OPTIMA 4TH GEN FACELIFT" = "HYUNDAI SONATA 2020" +"KIA OPTIMA HYBRID 2017 & SPORTS 2019" = "HYUNDAI SONATA 2020" +"KIA OPTIMA HYBRID 4TH GEN FACELIFT" = "HYUNDAI SONATA 2020" +"KIA FORTE E 2018 & GT 2021" = "HYUNDAI SONATA 2020" +"KIA CEED INTRO ED 2019" = "HYUNDAI SONATA 2020" +"KIA SELTOS 2021" = "HYUNDAI SONATA 2020" +"KIA NIRO HYBRID 2019" = "KIA NIRO EV 2020" +"KIA NIRO PLUG-IN HYBRID 2022" = "KIA NIRO EV 2020" +"KIA NIRO HYBRID 2021" = "KIA NIRO EV 2020" +"HYUNDAI VELOSTER 2019" = "HYUNDAI SONATA 2019" +"HYUNDAI KONA 2020" = "HYUNDAI KONA ELECTRIC 2019" +"HYUNDAI KONA HYBRID 2020" = "HYUNDAI KONA ELECTRIC 2019" +"HYUNDAI KONA ELECTRIC 2022" = "HYUNDAI KONA ELECTRIC 2019" +"HYUNDAI IONIQ HYBRID 2017-2019" = "HYUNDAI IONIQ PLUG-IN HYBRID 2019" +"HYUNDAI IONIQ HYBRID 2020-2022" = "HYUNDAI IONIQ PLUG-IN HYBRID 2019" +"HYUNDAI IONIQ ELECTRIC 2020" = "HYUNDAI IONIQ PLUG-IN HYBRID 2019" +"HYUNDAI ELANTRA 2017" = "HYUNDAI SONATA 2019" +"HYUNDAI I30 N LINE 2019 & GT 2018 DCT" = "HYUNDAI SONATA 2019" +"HYUNDAI ELANTRA HYBRID 2021" = "HYUNDAI SONATA 2020" +"HYUNDAI TUCSON 2019" = "HYUNDAI SANTA FE 2019" +"HYUNDAI SANTA FE 2022" = "HYUNDAI SANTA FE HYBRID 2022" +"KIA K5 HYBRID 2020" = "KIA K5 2021" +"KIA STINGER 2022" = "KIA STINGER GT2 2018" +"GENESIS G90 2017" = "GENESIS G70 2018" +"GENESIS G80 2017" = "GENESIS G70 2018" +"GENESIS G70 2020" = "HYUNDAI SONATA 2020" + +"HONDA FREED 2020" = "HONDA ODYSSEY 2018" +"HONDA CR-V EU 2016" = "HONDA CR-V 2016" +"HONDA CIVIC SEDAN 1.6 DIESEL 2019" = "HONDA CIVIC (BOSCH) 2019" +"HONDA E 2020" = "HONDA CIVIC (BOSCH) 2019" +"HONDA ODYSSEY CHN 2019" = "HONDA ODYSSEY 2018" + +"BUICK LACROSSE 2017" = "CHEVROLET VOLT PREMIER 2017" +"BUICK REGAL ESSENCE 2018" = "CHEVROLET VOLT PREMIER 2017" +"CADILLAC ESCALADE ESV 2016" = "CHEVROLET VOLT PREMIER 2017" +"CADILLAC ATS Premium Performance 2018" = "CHEVROLET VOLT PREMIER 2017" +"CHEVROLET MALIBU PREMIER 2017" = "CHEVROLET VOLT PREMIER 2017" +"HOLDEN ASTRA RS-V BK 2017" = "CHEVROLET VOLT PREMIER 2017" + +"SKODA FABIA 4TH GEN" = "VOLKSWAGEN GOLF 7TH GEN" +"SKODA OCTAVIA 3RD GEN" = "SKODA SUPERB 3RD GEN" +"SKODA SCALA 1ST GEN" = "SKODA SUPERB 3RD GEN" +"SKODA KODIAQ 1ST GEN" = "SKODA SUPERB 3RD GEN" +"SKODA KAROQ 1ST GEN" = "SKODA SUPERB 3RD GEN" +"SKODA KAMIQ 1ST GEN" = "SKODA SUPERB 3RD GEN" +"VOLKSWAGEN CRAFTER 2ND GEN" = "VOLKSWAGEN TIGUAN 2ND GEN" +"VOLKSWAGEN T-ROC 1ST GEN" = "VOLKSWAGEN TIGUAN 2ND GEN" +"VOLKSWAGEN T-CROSS 1ST GEN" = "VOLKSWAGEN TIGUAN 2ND GEN" +"VOLKSWAGEN TOURAN 2ND GEN" = "VOLKSWAGEN TIGUAN 2ND GEN" +"VOLKSWAGEN TRANSPORTER T6.1" = "VOLKSWAGEN TIGUAN 2ND GEN" +"AUDI Q2 1ST GEN" = "VOLKSWAGEN TIGUAN 2ND GEN" +"VOLKSWAGEN TAOS 1ST GEN" = "VOLKSWAGEN TIGUAN 2ND GEN" +"VOLKSWAGEN POLO 6TH GEN" = "VOLKSWAGEN GOLF 7TH GEN" +"SEAT LEON 3RD GEN" = "VOLKSWAGEN GOLF 7TH GEN" +"SEAT ATECA 1ST GEN" = "VOLKSWAGEN GOLF 7TH GEN" + +"SUBARU CROSSTREK HYBRID 2020" = "SUBARU IMPREZA SPORT 2020" +"SUBARU FORESTER HYBRID 2020" = "SUBARU IMPREZA SPORT 2020" +"SUBARU LEGACY 7TH GEN" = "SUBARU OUTBACK 6TH GEN" + +# Old subarus don't have much data guessing it's like low torque impreza" +"SUBARU OUTBACK 2018 - 2019" = "SUBARU IMPREZA LIMITED 2019" +"SUBARU OUTBACK 2015 - 2017" = "SUBARU IMPREZA LIMITED 2019" +"SUBARU FORESTER 2017 - 2018" = "SUBARU IMPREZA LIMITED 2019" +"SUBARU LEGACY 2015 - 2018" = "SUBARU IMPREZA LIMITED 2019" +"SUBARU ASCENT LIMITED 2019" = "SUBARU FORESTER 2019" diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml deleted file mode 100644 index c7a1566b32..0000000000 --- a/selfdrive/car/torque_data/substitute.yaml +++ /dev/null @@ -1,82 +0,0 @@ -MAZDA 3: MAZDA CX-9 2021 -MAZDA 6: MAZDA CX-9 2021 -MAZDA CX-5: MAZDA CX-9 2021 -MAZDA CX-5 2022: MAZDA CX-9 2021 -MAZDA CX-9: MAZDA CX-9 2021 - -TOYOTA ALPHARD 2020: TOYOTA SIENNA 2018 -TOYOTA PRIUS v 2017 : TOYOTA PRIUS 2017 -LEXUS IS 2018: LEXUS NX 2018 -LEXUS CT HYBRID 2018 : LEXUS NX 2018 -LEXUS ES 2018: TOYOTA CAMRY 2018 -LEXUS ES HYBRID 2018: TOYOTA CAMRY 2018 -LEXUS RC 2020: LEXUS NX 2020 - -KIA OPTIMA 4TH GEN: HYUNDAI SONATA 2020 -KIA OPTIMA 4TH GEN FACELIFT: HYUNDAI SONATA 2020 -KIA OPTIMA HYBRID 2017 & SPORTS 2019: HYUNDAI SONATA 2020 -KIA OPTIMA HYBRID 4TH GEN FACELIFT: HYUNDAI SONATA 2020 -KIA FORTE E 2018 & GT 2021: HYUNDAI SONATA 2020 -KIA CEED INTRO ED 2019: HYUNDAI SONATA 2020 -KIA SELTOS 2021: HYUNDAI SONATA 2020 -KIA NIRO HYBRID 2019: KIA NIRO EV 2020 -KIA NIRO HYBRID 2021: KIA NIRO EV 2020 -HYUNDAI VELOSTER 2019: HYUNDAI SONATA 2019 -HYUNDAI KONA 2020: HYUNDAI KONA ELECTRIC 2019 -HYUNDAI KONA HYBRID 2020: HYUNDAI KONA ELECTRIC 2019 -HYUNDAI KONA ELECTRIC 2022: HYUNDAI KONA ELECTRIC 2019 -HYUNDAI IONIQ HYBRID 2017-2019: HYUNDAI IONIQ PLUG-IN HYBRID 2019 -HYUNDAI IONIQ HYBRID 2020-2022: HYUNDAI IONIQ PLUG-IN HYBRID 2019 -HYUNDAI IONIQ ELECTRIC 2020: HYUNDAI IONIQ PLUG-IN HYBRID 2019 -HYUNDAI ELANTRA 2017: HYUNDAI SONATA 2019 -HYUNDAI I30 N LINE 2019 & GT 2018 DCT: HYUNDAI SONATA 2019 -HYUNDAI ELANTRA HYBRID 2021: HYUNDAI SONATA 2020 -HYUNDAI TUCSON 2019: HYUNDAI SANTA FE 2019 -HYUNDAI TUCSON 4TH GEN: HYUNDAI TUCSON HYBRID 4TH GEN -HYUNDAI SANTA FE 2022: HYUNDAI SANTA FE HYBRID 2022 -KIA K5 HYBRID 2020: KIA K5 2021 -KIA STINGER 2022: KIA STINGER GT2 2018 -GENESIS G90 2017: GENESIS G70 2018 -GENESIS G80 2017: GENESIS G70 2018 -GENESIS G70 2020: HYUNDAI SONATA 2020 - -HONDA FREED 2020: HONDA ODYSSEY 2018 -HONDA CR-V EU 2016: HONDA CR-V 2016 -HONDA CIVIC SEDAN 1.6 DIESEL 2019: HONDA CIVIC (BOSCH) 2019 -HONDA E 2020: HONDA CIVIC (BOSCH) 2019 -HONDA ODYSSEY CHN 2019: HONDA ODYSSEY 2018 - -BUICK LACROSSE 2017: CHEVROLET VOLT PREMIER 2017 -BUICK REGAL ESSENCE 2018: CHEVROLET VOLT PREMIER 2017 -CADILLAC ESCALADE ESV 2016: CHEVROLET VOLT PREMIER 2017 -CADILLAC ATS Premium Performance 2018: CHEVROLET VOLT PREMIER 2017 -CHEVROLET MALIBU PREMIER 2017: CHEVROLET VOLT PREMIER 2017 -HOLDEN ASTRA RS-V BK 2017: CHEVROLET VOLT PREMIER 2017 - -SKODA FABIA 4TH GEN: VOLKSWAGEN GOLF 7TH GEN -SKODA OCTAVIA 3RD GEN: SKODA SUPERB 3RD GEN -SKODA SCALA 1ST GEN: SKODA SUPERB 3RD GEN -SKODA KODIAQ 1ST GEN: SKODA SUPERB 3RD GEN -SKODA KAROQ 1ST GEN: SKODA SUPERB 3RD GEN -SKODA KAMIQ 1ST GEN: SKODA SUPERB 3RD GEN -VOLKSWAGEN CRAFTER 2ND GEN: VOLKSWAGEN TIGUAN 2ND GEN -VOLKSWAGEN T-ROC 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN -VOLKSWAGEN T-CROSS 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN -VOLKSWAGEN TOURAN 2ND GEN: VOLKSWAGEN TIGUAN 2ND GEN -VOLKSWAGEN TRANSPORTER T6.1: VOLKSWAGEN TIGUAN 2ND GEN -AUDI Q2 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN -VOLKSWAGEN TAOS 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN -VOLKSWAGEN POLO 6TH GEN: VOLKSWAGEN GOLF 7TH GEN -SEAT LEON 3RD GEN: VOLKSWAGEN GOLF 7TH GEN -SEAT ATECA 1ST GEN: VOLKSWAGEN GOLF 7TH GEN - -SUBARU CROSSTREK HYBRID 2020: SUBARU IMPREZA SPORT 2020 -SUBARU FORESTER HYBRID 2020: SUBARU IMPREZA SPORT 2020 -SUBARU LEGACY 7TH GEN: SUBARU OUTBACK 6TH GEN - -# Old subarus don't have much data guessing it's like low torque impreza -SUBARU OUTBACK 2018 - 2019: SUBARU IMPREZA LIMITED 2019 -SUBARU OUTBACK 2015 - 2017: SUBARU IMPREZA LIMITED 2019 -SUBARU FORESTER 2017 - 2018: SUBARU IMPREZA LIMITED 2019 -SUBARU LEGACY 2015 - 2018: SUBARU IMPREZA LIMITED 2019 -SUBARU ASCENT LIMITED 2019: SUBARU FORESTER 2019 diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 2a02a57d86..343b1d3031 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -21,8 +21,8 @@ MAX_USER_TORQUE = 500 # LTA limits # EPS ignores commands above this angle and causes PCS to fault -MAX_STEER_ANGLE = 94.9461 # deg -MAX_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes +MAX_LTA_ANGLE = 94.9461 # deg +MAX_LTA_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes class CarController: @@ -55,10 +55,10 @@ class CarController: apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params) # >100 degree/sec steering fault prevention - self.steer_rate_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE, CC.latActive, + self.steer_rate_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE, lat_active, self.steer_rate_counter, MAX_STEER_RATE_FRAMES) - if not CC.latActive: + if not lat_active: apply_steer = 0 # *** steer angle *** @@ -71,31 +71,38 @@ class CarController: apply_angle = actuators.steeringAngleDeg + CS.out.steeringAngleOffsetDeg # Angular rate limit based on speed - apply_angle = apply_std_steer_angle_limits(apply_angle, self.last_angle, CS.out.vEgo, self.params) + apply_angle = apply_std_steer_angle_limits(apply_angle, self.last_angle, CS.out.vEgoRaw, self.params) if not lat_active: apply_angle = CS.out.steeringAngleDeg + CS.out.steeringAngleOffsetDeg - self.last_angle = clip(apply_angle, -MAX_STEER_ANGLE, MAX_STEER_ANGLE) + self.last_angle = clip(apply_angle, -MAX_LTA_ANGLE, MAX_LTA_ANGLE) self.last_steer = apply_steer - # toyota can trace shows this message at 42Hz, with counter adding alternatively 1 and 2; + # toyota can trace shows STEERING_LKA at 42Hz, with counter adding alternatively 1 and 2; # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed # on consecutive messages can_sends.append(toyotacan.create_steer_command(self.packer, apply_steer, apply_steer_req)) + + # STEERING_LTA does not seem to allow more rate by sending faster, and may wind up easier if self.frame % 2 == 0 and self.CP.carFingerprint in TSS2_CAR: lta_active = lat_active and self.CP.steerControlType == SteerControlType.angle + # cut steering torque with TORQUE_WIND_DOWN when either EPS torque or driver torque is above + # the threshold, to limit max lateral acceleration and for driver torque blending respectively. full_torque_condition = (abs(CS.out.steeringTorqueEps) < self.params.STEER_MAX and - abs(CS.out.steeringTorque) < MAX_DRIVER_TORQUE_ALLOWANCE) - setme_x64 = 100 if lta_active and full_torque_condition else 0 - can_sends.append(toyotacan.create_lta_steer_command(self.packer, self.last_angle, lta_active, self.frame // 2, setme_x64)) + abs(CS.out.steeringTorque) < MAX_LTA_DRIVER_TORQUE_ALLOWANCE) + + # TORQUE_WIND_DOWN at 0 ramps down torque at roughly the max down rate of 1500 units/sec + torque_wind_down = 100 if lta_active and full_torque_condition else 0 + can_sends.append(toyotacan.create_lta_steer_command(self.packer, self.CP.steerControlType, self.last_angle, + lta_active, self.frame // 2, torque_wind_down)) # *** gas and brake *** if self.CP.enableGasInterceptor and CC.longActive: MAX_INTERCEPTOR_GAS = 0.5 # RAV4 has very sensitive gas pedal - if self.CP.carFingerprint in (CAR.RAV4, CAR.RAV4H, CAR.HIGHLANDER, CAR.HIGHLANDERH): + if self.CP.carFingerprint in (CAR.RAV4, CAR.RAV4H, CAR.HIGHLANDER): PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.15, 0.3, 0.0]) elif self.CP.carFingerprint in (CAR.COROLLA,): PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.3, 0.4, 0.0]) diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 3a89d655da..e4ea0d30f9 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -71,7 +71,7 @@ class CarState(CarStateBase): ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) ret.vEgoCluster = ret.vEgo * 1.015 # minimum of all the cars - ret.standstill = ret.vEgoRaw == 0 + ret.standstill = abs(ret.vEgoRaw) < 1e-3 ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + cp.vl["STEER_ANGLE_SENSOR"]["STEER_FRACTION"] ret.steeringRateDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_RATE"] @@ -95,6 +95,9 @@ class CarState(CarStateBase): ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 + if self.CP.carFingerprint != CAR.MIRAI: + ret.engineRpm = cp.vl["ENGINE_RPM"]["RPM"] + ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] * self.eps_torque_scale # we could use the override bit from dbc, but it's triggered at too high torque values @@ -180,6 +183,9 @@ class CarState(CarStateBase): ("STEER_TORQUE_SENSOR", 50), ] + if CP.carFingerprint != CAR.MIRAI: + messages.append(("ENGINE_RPM", 42)) + if CP.carFingerprint in UNSUPPORTED_DSU_CAR: messages.append(("DSU_CRUISE", 5)) messages.append(("PCM_CRUISE_ALT", 1)) diff --git a/selfdrive/car/toyota/fingerprints.py b/selfdrive/car/toyota/fingerprints.py new file mode 100644 index 0000000000..12a1d46aaf --- /dev/null +++ b/selfdrive/car/toyota/fingerprints.py @@ -0,0 +1,1652 @@ +from cereal import car +from openpilot.selfdrive.car.toyota.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.AVALON: { + (Ecu.abs, 0x7b0, None): [ + b'F152607060\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510701300\x00\x00\x00\x00', + b'881510705100\x00\x00\x00\x00', + b'881510705200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41051\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0701100\x00\x00\x00\x00', + b'8646F0703000\x00\x00\x00\x00', + ], + }, + CAR.AVALON_2019: { + (Ecu.abs, 0x7b0, None): [ + b'F152607110\x00\x00\x00\x00\x00\x00', + b'F152607140\x00\x00\x00\x00\x00\x00', + b'F152607171\x00\x00\x00\x00\x00\x00', + b'F152607180\x00\x00\x00\x00\x00\x00', + b'F152641040\x00\x00\x00\x00\x00\x00', + b'F152641050\x00\x00\x00\x00\x00\x00', + b'F152641060\x00\x00\x00\x00\x00\x00', + b'F152641061\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510703200\x00\x00\x00\x00', + b'881510704200\x00\x00\x00\x00', + b'881514107100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B07010\x00\x00\x00\x00\x00\x00', + b'8965B41070\x00\x00\x00\x00\x00\x00', + b'8965B41080\x00\x00\x00\x00\x00\x00', + b'8965B41090\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630725100\x00\x00\x00\x00', + b'\x01896630725200\x00\x00\x00\x00', + b'\x01896630725300\x00\x00\x00\x00', + b'\x01896630725400\x00\x00\x00\x00', + b'\x01896630735100\x00\x00\x00\x00', + b'\x01896630738000\x00\x00\x00\x00', + b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630734000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0702100\x00\x00\x00\x00', + ], + }, + CAR.AVALON_TSS2: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F152607240\x00\x00\x00\x00\x00\x00', + b'\x01F152607250\x00\x00\x00\x00\x00\x00', + b'\x01F152607280\x00\x00\x00\x00\x00\x00', + b'F152641080\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41110\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x01896630742000\x00\x00\x00\x00', + b'\x01896630743000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.CAMRY: { + (Ecu.engine, 0x700, None): [ + b'\x018966306L3100\x00\x00\x00\x00', + b'\x018966306L4200\x00\x00\x00\x00', + b'\x018966306L5200\x00\x00\x00\x00', + b'\x018966306L9000\x00\x00\x00\x00', + b'\x018966306P8000\x00\x00\x00\x00', + b'\x018966306Q3100\x00\x00\x00\x00', + b'\x018966306Q4000\x00\x00\x00\x00', + b'\x018966306Q4100\x00\x00\x00\x00', + b'\x018966306Q4200\x00\x00\x00\x00', + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x018966333N1100\x00\x00\x00\x00', + b'\x018966333N4300\x00\x00\x00\x00', + b'\x018966333P3100\x00\x00\x00\x00', + b'\x018966333P3200\x00\x00\x00\x00', + b'\x018966333P4200\x00\x00\x00\x00', + b'\x018966333P4300\x00\x00\x00\x00', + b'\x018966333P4400\x00\x00\x00\x00', + b'\x018966333P4500\x00\x00\x00\x00', + b'\x018966333P4700\x00\x00\x00\x00', + b'\x018966333P4900\x00\x00\x00\x00', + b'\x018966333Q6000\x00\x00\x00\x00', + b'\x018966333Q6200\x00\x00\x00\x00', + b'\x018966333Q6300\x00\x00\x00\x00', + b'\x018966333Q6500\x00\x00\x00\x00', + b'\x018966333Q9200\x00\x00\x00\x00', + b'\x018966333W6000\x00\x00\x00\x00', + b'\x018966333X0000\x00\x00\x00\x00', + b'\x018966333X4000\x00\x00\x00\x00', + b'\x01896633T16000\x00\x00\x00\x00', + b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821F0601200 ', + b'8821F0601300 ', + b'8821F0601400 ', + b'8821F0601500 ', + b'8821F0602000 ', + b'8821F0603300 ', + b'8821F0603400 ', + b'8821F0604000 ', + b'8821F0604100 ', + b'8821F0604200 ', + b'8821F0605200 ', + b'8821F0606200 ', + b'8821F0607200 ', + b'8821F0608000 ', + b'8821F0608200 ', + b'8821F0609000 ', + b'8821F0609100 ', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152606210\x00\x00\x00\x00\x00\x00', + b'F152606230\x00\x00\x00\x00\x00\x00', + b'F152606270\x00\x00\x00\x00\x00\x00', + b'F152606290\x00\x00\x00\x00\x00\x00', + b'F152606410\x00\x00\x00\x00\x00\x00', + b'F152633214\x00\x00\x00\x00\x00\x00', + b'F152633540\x00\x00\x00\x00\x00\x00', + b'F152633660\x00\x00\x00\x00\x00\x00', + b'F152633712\x00\x00\x00\x00\x00\x00', + b'F152633713\x00\x00\x00\x00\x00\x00', + b'F152633A10\x00\x00\x00\x00\x00\x00', + b'F152633A20\x00\x00\x00\x00\x00\x00', + b'F152633B51\x00\x00\x00\x00\x00\x00', + b'F152633B60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33540\x00\x00\x00\x00\x00\x00', + b'8965B33542\x00\x00\x00\x00\x00\x00', + b'8965B33550\x00\x00\x00\x00\x00\x00', + b'8965B33551\x00\x00\x00\x00\x00\x00', + b'8965B33580\x00\x00\x00\x00\x00\x00', + b'8965B33581\x00\x00\x00\x00\x00\x00', + b'8965B33611\x00\x00\x00\x00\x00\x00', + b'8965B33621\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0601200 ', + b'8821F0601300 ', + b'8821F0601400 ', + b'8821F0601500 ', + b'8821F0602000 ', + b'8821F0603300 ', + b'8821F0603400 ', + b'8821F0604000 ', + b'8821F0604100 ', + b'8821F0604200 ', + b'8821F0605200 ', + b'8821F0606200 ', + b'8821F0607200 ', + b'8821F0608000 ', + b'8821F0608200 ', + b'8821F0609000 ', + b'8821F0609100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0601200 ', + b'8646F0601300 ', + b'8646F0601400 ', + b'8646F0603400 ', + b'8646F0603500 ', + b'8646F0604100 ', + b'8646F0605000 ', + b'8646F0606000 ', + b'8646F0606100 ', + b'8646F0607000 ', + b'8646F0607100 ', + ], + }, + CAR.CAMRY_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B33630\x00\x00\x00\x00\x00\x00', + b'8965B33640\x00\x00\x00\x00\x00\x00', + b'8965B33650\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152606370\x00\x00\x00\x00\x00\x00', + b'\x01F152606390\x00\x00\x00\x00\x00\x00', + b'\x01F152606400\x00\x00\x00\x00\x00\x00', + b'\x01F152606431\x00\x00\x00\x00\x00\x00', + b'F152633310\x00\x00\x00\x00\x00\x00', + b'F152633D00\x00\x00\x00\x00\x00\x00', + b'F152633D60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x018966306Q5000\x00\x00\x00\x00', + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x018966306Q7000\x00\x00\x00\x00', + b'\x018966306Q9000\x00\x00\x00\x00', + b'\x018966306R3000\x00\x00\x00\x00', + b'\x018966306R8000\x00\x00\x00\x00', + b'\x018966306T0000\x00\x00\x00\x00', + b'\x018966306T3100\x00\x00\x00\x00', + b'\x018966306T3200\x00\x00\x00\x00', + b'\x018966306T4000\x00\x00\x00\x00', + b'\x018966306T4100\x00\x00\x00\x00', + b'\x018966306V1000\x00\x00\x00\x00', + b'\x01896633T20000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F0602300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F3305300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F3305500\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.CHR: { + (Ecu.engine, 0x700, None): [ + b'\x01896631017100\x00\x00\x00\x00', + b'\x01896631017200\x00\x00\x00\x00', + b'\x01896631021100\x00\x00\x00\x00', + b'\x0189663F413100\x00\x00\x00\x00', + b'\x0189663F414100\x00\x00\x00\x00', + b'\x0189663F438000\x00\x00\x00\x00', + b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821F0W01000 ', + b'8821F0W01100 ', + b'8821FF401600 ', + b'8821FF402300 ', + b'8821FF402400 ', + b'8821FF404000 ', + b'8821FF404100 ', + b'8821FF405000 ', + b'8821FF405100 ', + b'8821FF406000 ', + b'8821FF407100 ', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152610012\x00\x00\x00\x00\x00\x00', + b'F152610013\x00\x00\x00\x00\x00\x00', + b'F152610014\x00\x00\x00\x00\x00\x00', + b'F152610020\x00\x00\x00\x00\x00\x00', + b'F152610040\x00\x00\x00\x00\x00\x00', + b'F152610153\x00\x00\x00\x00\x00\x00', + b'F152610190\x00\x00\x00\x00\x00\x00', + b'F152610200\x00\x00\x00\x00\x00\x00', + b'F152610210\x00\x00\x00\x00\x00\x00', + b'F152610220\x00\x00\x00\x00\x00\x00', + b'F152610230\x00\x00\x00\x00\x00\x00', + b'F1526F4034\x00\x00\x00\x00\x00\x00', + b'F1526F4044\x00\x00\x00\x00\x00\x00', + b'F1526F4073\x00\x00\x00\x00\x00\x00', + b'F1526F4121\x00\x00\x00\x00\x00\x00', + b'F1526F4122\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B10011\x00\x00\x00\x00\x00\x00', + b'8965B10020\x00\x00\x00\x00\x00\x00', + b'8965B10040\x00\x00\x00\x00\x00\x00', + b'8965B10050\x00\x00\x00\x00\x00\x00', + b'8965B10070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x0331036000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', + b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0W01000 ', + b'8821F0W01100 ', + b'8821FF401600 ', + b'8821FF402300 ', + b'8821FF402400 ', + b'8821FF404000 ', + b'8821FF404100 ', + b'8821FF405000 ', + b'8821FF405100 ', + b'8821FF406000 ', + b'8821FF407100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646FF401700 ', + b'8646FF401800 ', + b'8646FF402100 ', + b'8646FF404000 ', + b'8646FF406000 ', + b'8646FF407000 ', + b'8646FF407100 ', + ], + }, + CAR.CHR_TSS2: { + (Ecu.abs, 0x7b0, None): [ + b'F152610041\x00\x00\x00\x00\x00\x00', + b'F152610260\x00\x00\x00\x00\x00\x00', + b'F1526F4270\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B10091\x00\x00\x00\x00\x00\x00', + b'8965B10092\x00\x00\x00\x00\x00\x00', + b'8965B10110\x00\x00\x00\x00\x00\x00', + b'8965B10111\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x0189663F438000\x00\x00\x00\x00', + b'\x0189663F459000\x00\x00\x00\x00', + b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821FF410200\x00\x00\x00\x00', + b'\x018821FF410300\x00\x00\x00\x00', + b'\x018821FF410500\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', + b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', + b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', + ], + }, + CAR.COROLLA: { + (Ecu.engine, 0x7e0, None): [ + b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510201100\x00\x00\x00\x00', + b'881510201200\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152602190\x00\x00\x00\x00\x00\x00', + b'F152602191\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B02181\x00\x00\x00\x00\x00\x00', + b'8965B02191\x00\x00\x00\x00\x00\x00', + b'8965B48150\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0201101\x00\x00\x00\x00', + b'8646F0201200\x00\x00\x00\x00', + ], + }, + CAR.COROLLA_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630A22000\x00\x00\x00\x00', + b'\x01896630ZG2000\x00\x00\x00\x00', + b'\x01896630ZG5000\x00\x00\x00\x00', + b'\x01896630ZG5100\x00\x00\x00\x00', + b'\x01896630ZG5200\x00\x00\x00\x00', + b'\x01896630ZG5300\x00\x00\x00\x00', + b'\x01896630ZJ1000\x00\x00\x00\x00', + b'\x01896630ZP1000\x00\x00\x00\x00', + b'\x01896630ZP2000\x00\x00\x00\x00', + b'\x01896630ZQ5000\x00\x00\x00\x00', + b'\x01896630ZU8000\x00\x00\x00\x00', + b'\x01896630ZU9000\x00\x00\x00\x00', + b'\x01896630ZX4000\x00\x00\x00\x00', + b'\x018966312L8000\x00\x00\x00\x00', + b'\x018966312M0000\x00\x00\x00\x00', + b'\x018966312M9000\x00\x00\x00\x00', + b'\x018966312P9000\x00\x00\x00\x00', + b'\x018966312P9100\x00\x00\x00\x00', + b'\x018966312P9200\x00\x00\x00\x00', + b'\x018966312P9300\x00\x00\x00\x00', + b'\x018966312Q2300\x00\x00\x00\x00', + b'\x018966312Q8000\x00\x00\x00\x00', + b'\x018966312R0000\x00\x00\x00\x00', + b'\x018966312R0100\x00\x00\x00\x00', + b'\x018966312R0200\x00\x00\x00\x00', + b'\x018966312R1000\x00\x00\x00\x00', + b'\x018966312R1100\x00\x00\x00\x00', + b'\x018966312R3100\x00\x00\x00\x00', + b'\x018966312S5000\x00\x00\x00\x00', + b'\x018966312S7000\x00\x00\x00\x00', + b'\x018966312W3000\x00\x00\x00\x00', + b'\x018966312W9000\x00\x00\x00\x00', + b'\x01896637621000\x00\x00\x00\x00', + b'\x01896637623000\x00\x00\x00\x00', + b'\x01896637624000\x00\x00\x00\x00', + b'\x01896637626000\x00\x00\x00\x00', + b'\x01896637639000\x00\x00\x00\x00', + b'\x01896637643000\x00\x00\x00\x00', + b'\x01896637644000\x00\x00\x00\x00', + b'\x01896637648000\x00\x00\x00\x00', + b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', + b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x038966312T3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZN5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965B12350\x00\x00\x00\x00\x00\x00', + b'\x018965B12470\x00\x00\x00\x00\x00\x00', + b'\x018965B12490\x00\x00\x00\x00\x00\x00', + b'\x018965B12500\x00\x00\x00\x00\x00\x00', + b'\x018965B12510\x00\x00\x00\x00\x00\x00', + b'\x018965B12520\x00\x00\x00\x00\x00\x00', + b'\x018965B12530\x00\x00\x00\x00\x00\x00', + b'\x018965B1254000\x00\x00\x00\x00', + b'\x018965B1255000\x00\x00\x00\x00', + b'\x018965B1256000\x00\x00\x00\x00', + b'8965B12361\x00\x00\x00\x00\x00\x00', + b'8965B12451\x00\x00\x00\x00\x00\x00', + b'8965B16011\x00\x00\x00\x00\x00\x00', + b'8965B16101\x00\x00\x00\x00\x00\x00', + b'8965B16170\x00\x00\x00\x00\x00\x00', + b'8965B76012\x00\x00\x00\x00\x00\x00', + b'8965B76050\x00\x00\x00\x00\x00\x00', + b'8965B76091\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152602280\x00\x00\x00\x00\x00\x00', + b'\x01F152602470\x00\x00\x00\x00\x00\x00', + b'\x01F152602560\x00\x00\x00\x00\x00\x00', + b'\x01F152602590\x00\x00\x00\x00\x00\x00', + b'\x01F152602650\x00\x00\x00\x00\x00\x00', + b'\x01F15260A010\x00\x00\x00\x00\x00\x00', + b'\x01F15260A050\x00\x00\x00\x00\x00\x00', + b'\x01F15260A070\x00\x00\x00\x00\x00\x00', + b'\x01F152612641\x00\x00\x00\x00\x00\x00', + b'\x01F152612651\x00\x00\x00\x00\x00\x00', + b'\x01F152612862\x00\x00\x00\x00\x00\x00', + b'\x01F152612B10\x00\x00\x00\x00\x00\x00', + b'\x01F152612B51\x00\x00\x00\x00\x00\x00', + b'\x01F152612B60\x00\x00\x00\x00\x00\x00', + b'\x01F152612B61\x00\x00\x00\x00\x00\x00', + b'\x01F152612B62\x00\x00\x00\x00\x00\x00', + b'\x01F152612B70\x00\x00\x00\x00\x00\x00', + b'\x01F152612B71\x00\x00\x00\x00\x00\x00', + b'\x01F152612B81\x00\x00\x00\x00\x00\x00', + b'\x01F152612B90\x00\x00\x00\x00\x00\x00', + b'\x01F152612B91\x00\x00\x00\x00\x00\x00', + b'\x01F152612C00\x00\x00\x00\x00\x00\x00', + b'\x01F152676250\x00\x00\x00\x00\x00\x00', + b'F152612590\x00\x00\x00\x00\x00\x00', + b'F152612691\x00\x00\x00\x00\x00\x00', + b'F152612692\x00\x00\x00\x00\x00\x00', + b'F152612700\x00\x00\x00\x00\x00\x00', + b'F152612710\x00\x00\x00\x00\x00\x00', + b'F152612790\x00\x00\x00\x00\x00\x00', + b'F152612800\x00\x00\x00\x00\x00\x00', + b'F152612820\x00\x00\x00\x00\x00\x00', + b'F152612840\x00\x00\x00\x00\x00\x00', + b'F152612842\x00\x00\x00\x00\x00\x00', + b'F152612890\x00\x00\x00\x00\x00\x00', + b'F152612A00\x00\x00\x00\x00\x00\x00', + b'F152612A10\x00\x00\x00\x00\x00\x00', + b'F152612D00\x00\x00\x00\x00\x00\x00', + b'F152616011\x00\x00\x00\x00\x00\x00', + b'F152616030\x00\x00\x00\x00\x00\x00', + b'F152616060\x00\x00\x00\x00\x00\x00', + b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152676293\x00\x00\x00\x00\x00\x00', + b'F152676303\x00\x00\x00\x00\x00\x00', + b'F152676304\x00\x00\x00\x00\x00\x00', + b'F152676371\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1206000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7603300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.HIGHLANDER: { + (Ecu.engine, 0x700, None): [ + b'\x01896630E09000\x00\x00\x00\x00', + b'\x01896630E43000\x00\x00\x00\x00', + b'\x01896630E43100\x00\x00\x00\x00', + b'\x01896630E43200\x00\x00\x00\x00', + b'\x01896630E44200\x00\x00\x00\x00', + b'\x01896630E44400\x00\x00\x00\x00', + b'\x01896630E45000\x00\x00\x00\x00', + b'\x01896630E45100\x00\x00\x00\x00', + b'\x01896630E45200\x00\x00\x00\x00', + b'\x01896630E46000\x00\x00\x00\x00', + b'\x01896630E46200\x00\x00\x00\x00', + b'\x01896630E74000\x00\x00\x00\x00', + b'\x01896630E75000\x00\x00\x00\x00', + b'\x01896630E76000\x00\x00\x00\x00', + b'\x01896630E77000\x00\x00\x00\x00', + b'\x01896630E83000\x00\x00\x00\x00', + b'\x01896630E84000\x00\x00\x00\x00', + b'\x01896630E85000\x00\x00\x00\x00', + b'\x01896630E86000\x00\x00\x00\x00', + b'\x01896630E88000\x00\x00\x00\x00', + b'\x01896630EA0000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230E51000\x00\x00\x00\x00\x00\x00\x00\x0050E17000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48140\x00\x00\x00\x00\x00\x00', + b'8965B48150\x00\x00\x00\x00\x00\x00', + b'8965B48160\x00\x00\x00\x00\x00\x00', + b'8965B48210\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F15260E011\x00\x00\x00\x00\x00\x00', + b'F152648541\x00\x00\x00\x00\x00\x00', + b'F152648542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510E01100\x00\x00\x00\x00', + b'881510E01200\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0E01200\x00\x00\x00\x00', + b'8646F0E01300\x00\x00\x00\x00', + ], + }, + CAR.HIGHLANDER_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B48241\x00\x00\x00\x00\x00\x00', + b'8965B48310\x00\x00\x00\x00\x00\x00', + b'8965B48320\x00\x00\x00\x00\x00\x00', + b'8965B48400\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260E051\x00\x00\x00\x00\x00\x00', + b'\x01F15260E05300\x00\x00\x00\x00', + b'\x01F15260E061\x00\x00\x00\x00\x00\x00', + b'\x01F15260E110\x00\x00\x00\x00\x00\x00', + b'\x01F15260E170\x00\x00\x00\x00\x00\x00', + b'\x01F15264872300\x00\x00\x00\x00', + b'\x01F15264872400\x00\x00\x00\x00', + b'\x01F15264872500\x00\x00\x00\x00', + b'\x01F15264872600\x00\x00\x00\x00', + b'\x01F15264872700\x00\x00\x00\x00', + b'\x01F15264873500\x00\x00\x00\x00', + b'\x01F152648C6300\x00\x00\x00\x00', + b'\x01F152648J4000\x00\x00\x00\x00', + b'\x01F152648J5000\x00\x00\x00\x00', + b'\x01F152648J6000\x00\x00\x00\x00', + b'\x01F152648J7000\x00\x00\x00\x00', + b'\x01F152648L5000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630E62100\x00\x00\x00\x00', + b'\x01896630E62200\x00\x00\x00\x00', + b'\x01896630E64100\x00\x00\x00\x00', + b'\x01896630E64200\x00\x00\x00\x00', + b'\x01896630E64400\x00\x00\x00\x00', + b'\x01896630E67000\x00\x00\x00\x00', + b'\x01896630EA1000\x00\x00\x00\x00', + b'\x01896630EB1000\x00\x00\x00\x00', + b'\x01896630EB1100\x00\x00\x00\x00', + b'\x01896630EB1200\x00\x00\x00\x00', + b'\x01896630EB2000\x00\x00\x00\x00', + b'\x01896630EB2100\x00\x00\x00\x00', + b'\x01896630EB2200\x00\x00\x00\x00', + b'\x01896630EC4000\x00\x00\x00\x00', + b'\x01896630ED9000\x00\x00\x00\x00', + b'\x01896630ED9100\x00\x00\x00\x00', + b'\x01896630EE1000\x00\x00\x00\x00', + b'\x01896630EE1100\x00\x00\x00\x00', + b'\x01896630EE4000\x00\x00\x00\x00', + b'\x01896630EE4100\x00\x00\x00\x00', + b'\x01896630EE5000\x00\x00\x00\x00', + b'\x01896630EE6000\x00\x00\x00\x00', + b'\x01896630EE7000\x00\x00\x00\x00', + b'\x01896630EF8000\x00\x00\x00\x00', + b'\x01896630EG3000\x00\x00\x00\x00', + b'\x01896630EG5000\x00\x00\x00\x00', + b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_IS: { + (Ecu.engine, 0x700, None): [ + b'\x018966353M7000\x00\x00\x00\x00', + b'\x018966353M7100\x00\x00\x00\x00', + b'\x018966353Q2000\x00\x00\x00\x00', + b'\x018966353Q2300\x00\x00\x00\x00', + b'\x018966353Q4000\x00\x00\x00\x00', + b'\x018966353R1100\x00\x00\x00\x00', + b'\x018966353R7100\x00\x00\x00\x00', + b'\x018966353R8000\x00\x00\x00\x00', + b'\x018966353R8100\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152653300\x00\x00\x00\x00\x00\x00', + b'F152653301\x00\x00\x00\x00\x00\x00', + b'F152653310\x00\x00\x00\x00\x00\x00', + b'F152653330\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881515306200\x00\x00\x00\x00', + b'881515306400\x00\x00\x00\x00', + b'881515306500\x00\x00\x00\x00', + b'881515307400\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B53270\x00\x00\x00\x00\x00\x00', + b'8965B53271\x00\x00\x00\x00\x00\x00', + b'8965B53280\x00\x00\x00\x00\x00\x00', + b'8965B53281\x00\x00\x00\x00\x00\x00', + b'8965B53311\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F5301101\x00\x00\x00\x00', + b'8646F5301200\x00\x00\x00\x00', + b'8646F5301300\x00\x00\x00\x00', + b'8646F5301400\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_IS_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966353S1000\x00\x00\x00\x00', + b'\x018966353S2000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15265337200\x00\x00\x00\x00', + b'\x01F15265342000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B53450\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.PRIUS: { + (Ecu.engine, 0x700, None): [ + b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634762100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634770100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', + b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', + b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B47021\x00\x00\x00\x00\x00\x00', + b'8965B47022\x00\x00\x00\x00\x00\x00', + b'8965B47023\x00\x00\x00\x00\x00\x00', + b'8965B47050\x00\x00\x00\x00\x00\x00', + b'8965B47060\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152647290\x00\x00\x00\x00\x00\x00', + b'F152647300\x00\x00\x00\x00\x00\x00', + b'F152647310\x00\x00\x00\x00\x00\x00', + b'F152647414\x00\x00\x00\x00\x00\x00', + b'F152647415\x00\x00\x00\x00\x00\x00', + b'F152647416\x00\x00\x00\x00\x00\x00', + b'F152647417\x00\x00\x00\x00\x00\x00', + b'F152647470\x00\x00\x00\x00\x00\x00', + b'F152647490\x00\x00\x00\x00\x00\x00', + b'F152647682\x00\x00\x00\x00\x00\x00', + b'F152647683\x00\x00\x00\x00\x00\x00', + b'F152647684\x00\x00\x00\x00\x00\x00', + b'F152647862\x00\x00\x00\x00\x00\x00', + b'F152647863\x00\x00\x00\x00\x00\x00', + b'F152647864\x00\x00\x00\x00\x00\x00', + b'F152647865\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514702300\x00\x00\x00\x00', + b'881514702400\x00\x00\x00\x00', + b'881514703100\x00\x00\x00\x00', + b'881514704100\x00\x00\x00\x00', + b'881514706000\x00\x00\x00\x00', + b'881514706100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4701300\x00\x00\x00\x00', + b'8646F4702001\x00\x00\x00\x00', + b'8646F4702100\x00\x00\x00\x00', + b'8646F4702200\x00\x00\x00\x00', + b'8646F4705000\x00\x00\x00\x00', + b'8646F4705200\x00\x00\x00\x00', + ], + }, + CAR.PRIUS_V: { + (Ecu.abs, 0x7b0, None): [ + b'F152647280\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514705100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4703300\x00\x00\x00\x00', + ], + }, + CAR.RAV4: { + (Ecu.engine, 0x7e0, None): [ + b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B42063\x00\x00\x00\x00\x00\x00', + b'8965B42073\x00\x00\x00\x00\x00\x00', + b'8965B42082\x00\x00\x00\x00\x00\x00', + b'8965B42083\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F15260R102\x00\x00\x00\x00\x00\x00', + b'F15260R103\x00\x00\x00\x00\x00\x00', + b'F152642492\x00\x00\x00\x00\x00\x00', + b'F152642493\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514201200\x00\x00\x00\x00', + b'881514201300\x00\x00\x00\x00', + b'881514201400\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4201100\x00\x00\x00\x00', + b'8646F4201200\x00\x00\x00\x00', + b'8646F4202001\x00\x00\x00\x00', + b'8646F4202100\x00\x00\x00\x00', + b'8646F4204000\x00\x00\x00\x00', + ], + }, + CAR.RAV4H: { + (Ecu.engine, 0x7e0, None): [ + b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B42102\x00\x00\x00\x00\x00\x00', + b'8965B42103\x00\x00\x00\x00\x00\x00', + b'8965B42112\x00\x00\x00\x00\x00\x00', + b'8965B42162\x00\x00\x00\x00\x00\x00', + b'8965B42163\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152642090\x00\x00\x00\x00\x00\x00', + b'F152642110\x00\x00\x00\x00\x00\x00', + b'F152642120\x00\x00\x00\x00\x00\x00', + b'F152642400\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514202200\x00\x00\x00\x00', + b'881514202300\x00\x00\x00\x00', + b'881514202400\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4201100\x00\x00\x00\x00', + b'8646F4201200\x00\x00\x00\x00', + b'8646F4202001\x00\x00\x00\x00', + b'8646F4202100\x00\x00\x00\x00', + b'8646F4204000\x00\x00\x00\x00', + ], + }, + CAR.RAV4_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630R58000\x00\x00\x00\x00', + b'\x01896630R58100\x00\x00\x00\x00', + b'\x018966342E2000\x00\x00\x00\x00', + b'\x018966342M5000\x00\x00\x00\x00', + b'\x018966342M8000\x00\x00\x00\x00', + b'\x018966342S9000\x00\x00\x00\x00', + b'\x018966342T1000\x00\x00\x00\x00', + b'\x018966342T6000\x00\x00\x00\x00', + b'\x018966342T9000\x00\x00\x00\x00', + b'\x018966342U4000\x00\x00\x00\x00', + b'\x018966342U4100\x00\x00\x00\x00', + b'\x018966342U5100\x00\x00\x00\x00', + b'\x018966342V0000\x00\x00\x00\x00', + b'\x018966342V3000\x00\x00\x00\x00', + b'\x018966342V3100\x00\x00\x00\x00', + b'\x018966342V3200\x00\x00\x00\x00', + b'\x018966342W5000\x00\x00\x00\x00', + b'\x018966342W7000\x00\x00\x00\x00', + b'\x018966342W8000\x00\x00\x00\x00', + b'\x018966342X5000\x00\x00\x00\x00', + b'\x018966342X6000\x00\x00\x00\x00', + b'\x01896634A05000\x00\x00\x00\x00', + b'\x01896634A15000\x00\x00\x00\x00', + b'\x01896634A19000\x00\x00\x00\x00', + b'\x01896634A19100\x00\x00\x00\x00', + b'\x01896634A20000\x00\x00\x00\x00', + b'\x01896634A20100\x00\x00\x00\x00', + b'\x01896634A22000\x00\x00\x00\x00', + b'\x01896634A22100\x00\x00\x00\x00', + b'\x01896634A25000\x00\x00\x00\x00', + b'\x01896634A30000\x00\x00\x00\x00', + b'\x01896634A44000\x00\x00\x00\x00', + b'\x01896634A45000\x00\x00\x00\x00', + b'\x01896634A46000\x00\x00\x00\x00', + b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', + b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R210\x00\x00\x00\x00\x00\x00', + b'\x01F15260R220\x00\x00\x00\x00\x00\x00', + b'\x01F15260R290\x00\x00\x00\x00\x00\x00', + b'\x01F15260R292\x00\x00\x00\x00\x00\x00', + b'\x01F15260R300\x00\x00\x00\x00\x00\x00', + b'\x01F15260R302\x00\x00\x00\x00\x00\x00', + b'\x01F152642551\x00\x00\x00\x00\x00\x00', + b'\x01F152642561\x00\x00\x00\x00\x00\x00', + b'\x01F152642601\x00\x00\x00\x00\x00\x00', + b'\x01F152642700\x00\x00\x00\x00\x00\x00', + b'\x01F152642701\x00\x00\x00\x00\x00\x00', + b'\x01F152642710\x00\x00\x00\x00\x00\x00', + b'\x01F152642711\x00\x00\x00\x00\x00\x00', + b'\x01F152642750\x00\x00\x00\x00\x00\x00', + b'\x01F152642751\x00\x00\x00\x00\x00\x00', + b'F152642290\x00\x00\x00\x00\x00\x00', + b'F152642291\x00\x00\x00\x00\x00\x00', + b'F152642322\x00\x00\x00\x00\x00\x00', + b'F152642330\x00\x00\x00\x00\x00\x00', + b'F152642331\x00\x00\x00\x00\x00\x00', + b'F152642520\x00\x00\x00\x00\x00\x00', + b'F152642521\x00\x00\x00\x00\x00\x00', + b'F152642531\x00\x00\x00\x00\x00\x00', + b'F152642532\x00\x00\x00\x00\x00\x00', + b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152642541\x00\x00\x00\x00\x00\x00', + b'F152642542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', + b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', + b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', + b'8965B42170\x00\x00\x00\x00\x00\x00', + b'8965B42171\x00\x00\x00\x00\x00\x00', + b'8965B42180\x00\x00\x00\x00\x00\x00', + b'8965B42181\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + ], + }, + CAR.RAV4_TSS2_2022: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R350\x00\x00\x00\x00\x00\x00', + b'\x01F15260R361\x00\x00\x00\x00\x00\x00', + b'\x01F15264283100\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264286100\x00\x00\x00\x00', + b'\x01F15264286200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', + b'8965B42172\x00\x00\x00\x00\x00\x00', + b'8965B42182\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896634A02001\x00\x00\x00\x00', + b'\x01896634A03000\x00\x00\x00\x00', + b'\x01896634A08000\x00\x00\x00\x00', + b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A62000\x00\x00\x00\x00', + b'\x01896634A62100\x00\x00\x00\x00', + b'\x01896634A63000\x00\x00\x00\x00', + b'\x01896634A88000\x00\x00\x00\x00', + b'\x01896634A89000\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', + b'\x01896634AA0000\x00\x00\x00\x00', + b'\x01896634AA0100\x00\x00\x00\x00', + b'\x01896634AA1000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0R01100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', + ], + }, + CAR.RAV4_TSS2_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R450\x00\x00\x00\x00\x00\x00', + b'\x01F15260R51000\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264283300\x00\x00\x00\x00', + b'\x01F152642F1000\x00\x00\x00\x00', + b'\x01F152642F8000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', + b'8965B42371\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896634A88100\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', + b'\x01896634AE1001\x00\x00\x00\x00', + b'\x01896634AF0000\x00\x00\x00\x00', + b'\x01896634AJ2000\x00\x00\x00\x00', + b'\x01896634AL5000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0R03100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', + b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', + b'\x028646F0R11000\x00\x00\x00\x008646G0R04000\x00\x00\x00\x00', + ], + }, + CAR.SIENNA: { + (Ecu.engine, 0x700, None): [ + b'\x01896630832100\x00\x00\x00\x00', + b'\x01896630832200\x00\x00\x00\x00', + b'\x01896630838000\x00\x00\x00\x00', + b'\x01896630838100\x00\x00\x00\x00', + b'\x01896630842000\x00\x00\x00\x00', + b'\x01896630843000\x00\x00\x00\x00', + b'\x01896630851000\x00\x00\x00\x00', + b'\x01896630851100\x00\x00\x00\x00', + b'\x01896630851200\x00\x00\x00\x00', + b'\x01896630852000\x00\x00\x00\x00', + b'\x01896630852100\x00\x00\x00\x00', + b'\x01896630859000\x00\x00\x00\x00', + b'\x01896630860000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B45070\x00\x00\x00\x00\x00\x00', + b'8965B45080\x00\x00\x00\x00\x00\x00', + b'8965B45082\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152608130\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510801100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702200\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0801100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_CTH: { + (Ecu.dsu, 0x791, None): [ + b'881517601100\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152676144\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237635000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F7601100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_ES_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966306U6000\x00\x00\x00\x00', + b'\x018966333T5000\x00\x00\x00\x00', + b'\x018966333T5100\x00\x00\x00\x00', + b'\x018966333X6000\x00\x00\x00\x00', + b'\x01896633T07000\x00\x00\x00\x00', + b'\x01896633T38000\x00\x00\x00\x00', + b'\x01896633T58000\x00\x00\x00\x00', + b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152606281\x00\x00\x00\x00\x00\x00', + b'\x01F152606340\x00\x00\x00\x00\x00\x00', + b'\x01F152606461\x00\x00\x00\x00\x00\x00', + b'\x01F15260646200\x00\x00\x00\x00', + b'F152633423\x00\x00\x00\x00\x00\x00', + b'F152633680\x00\x00\x00\x00\x00\x00', + b'F152633681\x00\x00\x00\x00\x00\x00', + b'F152633F50\x00\x00\x00\x00\x00\x00', + b'F152633F51\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33252\x00\x00\x00\x00\x00\x00', + b'8965B33590\x00\x00\x00\x00\x00\x00', + b'8965B33690\x00\x00\x00\x00\x00\x00', + b'8965B33721\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3309100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_ES: { + (Ecu.engine, 0x7e0, None): [ + b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152606202\x00\x00\x00\x00\x00\x00', + b'F152633171\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881513309400\x00\x00\x00\x00', + b'881513309500\x00\x00\x00\x00', + b'881513310400\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33502\x00\x00\x00\x00\x00\x00', + b'8965B33512\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F3302001\x00\x00\x00\x00', + b'8646F3302100\x00\x00\x00\x00', + b'8646F3302200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_GS_F: { + (Ecu.engine, 0x7e0, None): [ + b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152630700\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881513016200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B30551\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F3002100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_NX: { + (Ecu.engine, 0x700, None): [ + b'\x01896637850000\x00\x00\x00\x00', + b'\x01896637851000\x00\x00\x00\x00', + b'\x01896637852000\x00\x00\x00\x00', + b'\x01896637854000\x00\x00\x00\x00', + b'\x01896637873000\x00\x00\x00\x00', + b'\x01896637878000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152678130\x00\x00\x00\x00\x00\x00', + b'F152678140\x00\x00\x00\x00\x00\x00', + b'F152678160\x00\x00\x00\x00\x00\x00', + b'F152678170\x00\x00\x00\x00\x00\x00', + b'F152678171\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881517803100\x00\x00\x00\x00', + b'881517803300\x00\x00\x00\x00', + b'881517804100\x00\x00\x00\x00', + b'881517804300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78060\x00\x00\x00\x00\x00\x00', + b'8965B78080\x00\x00\x00\x00\x00\x00', + b'8965B78100\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F7801100\x00\x00\x00\x00', + b'8646F7801300\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_NX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966378B2000\x00\x00\x00\x00', + b'\x018966378B2100\x00\x00\x00\x00', + b'\x018966378B3000\x00\x00\x00\x00', + b'\x018966378B3100\x00\x00\x00\x00', + b'\x018966378B4100\x00\x00\x00\x00', + b'\x018966378G2000\x00\x00\x00\x00', + b'\x018966378G3000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237881000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152678221\x00\x00\x00\x00\x00\x00', + b'F152678200\x00\x00\x00\x00\x00\x00', + b'F152678210\x00\x00\x00\x00\x00\x00', + b'F152678211\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78110\x00\x00\x00\x00\x00\x00', + b'8965B78120\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_LC_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x0131130000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152611390\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B11091\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F1105200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RC: { + (Ecu.engine, 0x700, None): [ + b'\x01896632461100\x00\x00\x00\x00', + b'\x01896632478100\x00\x00\x00\x00', + b'\x01896632478200\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152624150\x00\x00\x00\x00\x00\x00', + b'F152624221\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881512404100\x00\x00\x00\x00', + b'881512407000\x00\x00\x00\x00', + b'881512409100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B24081\x00\x00\x00\x00\x00\x00', + b'8965B24240\x00\x00\x00\x00\x00\x00', + b'8965B24320\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F2401100\x00\x00\x00\x00', + b'8646F2401200\x00\x00\x00\x00', + b'8646F2402200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RX: { + (Ecu.engine, 0x700, None): [ + b'\x01896630E36100\x00\x00\x00\x00', + b'\x01896630E36200\x00\x00\x00\x00', + b'\x01896630E36300\x00\x00\x00\x00', + b'\x01896630E37100\x00\x00\x00\x00', + b'\x01896630E37200\x00\x00\x00\x00', + b'\x01896630E37300\x00\x00\x00\x00', + b'\x01896630E41000\x00\x00\x00\x00', + b'\x01896630E41100\x00\x00\x00\x00', + b'\x01896630E41200\x00\x00\x00\x00', + b'\x01896630E41500\x00\x00\x00\x00', + b'\x01896630EA3100\x00\x00\x00\x00', + b'\x01896630EA3400\x00\x00\x00\x00', + b'\x01896630EA4100\x00\x00\x00\x00', + b'\x01896630EA4300\x00\x00\x00\x00', + b'\x01896630EA4400\x00\x00\x00\x00', + b'\x01896630EA6300\x00\x00\x00\x00', + b'\x018966348R1300\x00\x00\x00\x00', + b'\x018966348R8500\x00\x00\x00\x00', + b'\x018966348W1300\x00\x00\x00\x00', + b'\x018966348W2300\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02348J7000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Q4100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1200\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152648361\x00\x00\x00\x00\x00\x00', + b'F152648472\x00\x00\x00\x00\x00\x00', + b'F152648473\x00\x00\x00\x00\x00\x00', + b'F152648474\x00\x00\x00\x00\x00\x00', + b'F152648492\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648494\x00\x00\x00\x00\x00\x00', + b'F152648501\x00\x00\x00\x00\x00\x00', + b'F152648502\x00\x00\x00\x00\x00\x00', + b'F152648504\x00\x00\x00\x00\x00\x00', + b'F152648630\x00\x00\x00\x00\x00\x00', + b'F152648740\x00\x00\x00\x00\x00\x00', + b'F152648A30\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514810300\x00\x00\x00\x00', + b'881514810500\x00\x00\x00\x00', + b'881514810700\x00\x00\x00\x00', + b'881514811300\x00\x00\x00\x00', + b'881514811500\x00\x00\x00\x00', + b'881514811700\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B0E011\x00\x00\x00\x00\x00\x00', + b'8965B0E012\x00\x00\x00\x00\x00\x00', + b'8965B48102\x00\x00\x00\x00\x00\x00', + b'8965B48111\x00\x00\x00\x00\x00\x00', + b'8965B48112\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701000\x00\x00\x00\x00', + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4801100\x00\x00\x00\x00', + b'8646F4801200\x00\x00\x00\x00', + b'8646F4802001\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', + b'8646F4802200\x00\x00\x00\x00', + b'8646F4809000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630EA9000\x00\x00\x00\x00', + b'\x01896630EB0000\x00\x00\x00\x00', + b'\x01896630EC9000\x00\x00\x00\x00', + b'\x01896630EC9100\x00\x00\x00\x00', + b'\x01896630ED0000\x00\x00\x00\x00', + b'\x01896630ED0100\x00\x00\x00\x00', + b'\x01896630ED5000\x00\x00\x00\x00', + b'\x01896630ED6000\x00\x00\x00\x00', + b'\x018966348R9200\x00\x00\x00\x00', + b'\x018966348T8000\x00\x00\x00\x00', + b'\x018966348W5100\x00\x00\x00\x00', + b'\x018966348W9000\x00\x00\x00\x00', + b'\x018966348X0000\x00\x00\x00\x00', + b'\x01896634D12000\x00\x00\x00\x00', + b'\x01896634D12100\x00\x00\x00\x00', + b'\x01896634D43000\x00\x00\x00\x00', + b'\x01896634D44000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260E031\x00\x00\x00\x00\x00\x00', + b'\x01F15260E041\x00\x00\x00\x00\x00\x00', + b'\x01F152648781\x00\x00\x00\x00\x00\x00', + b'\x01F152648801\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648811\x00\x00\x00\x00\x00\x00', + b'F152648831\x00\x00\x00\x00\x00\x00', + b'F152648891\x00\x00\x00\x00\x00\x00', + b'F152648C80\x00\x00\x00\x00\x00\x00', + b'F152648D00\x00\x00\x00\x00\x00\x00', + b'F152648D60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48261\x00\x00\x00\x00\x00\x00', + b'8965B48271\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, + CAR.PRIUS_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', + b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', + b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', + b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152647500\x00\x00\x00\x00\x00\x00', + b'F152647510\x00\x00\x00\x00\x00\x00', + b'F152647520\x00\x00\x00\x00\x00\x00', + b'F152647521\x00\x00\x00\x00\x00\x00', + b'F152647531\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B47070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + ], + }, + CAR.MIRAI: { + (Ecu.abs, 0x7d1, None): [ + b'\x01898A36203000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15266203200\x00\x00\x00\x00', + b'\x01F15266203500\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.ALPHARD_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B58040\x00\x00\x00\x00\x00\x00', + b'8965B58052\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152658320\x00\x00\x00\x00\x00\x00', + b'F152658341\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, +} diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 9cf86d69ab..988b1b4547 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -28,12 +28,11 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_ALT_BRAKE if candidate in ANGLE_CONTROL_CAR: - ret.dashcamOnly = True ret.steerControlType = SteerControlType.angle ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_LTA # LTA control can be more delayed and winds up more often - ret.steerActuatorDelay = 0.25 + ret.steerActuatorDelay = 0.18 ret.steerLimitTimer = 0.8 else: CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) @@ -77,7 +76,7 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 2860. * CV.LB_TO_KG # mean between normal and hybrid - elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RXH, CAR.LEXUS_RX_TSS2): + elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2): stop_and_go = True ret.wheelbase = 2.79 ret.steerRatio = 16. # 14.8 is spec end-to-end @@ -99,7 +98,8 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFactor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG # mean between normal and hybrid - elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.HIGHLANDER_TSS2): + elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDER_TSS2): + # TODO: TSS-P models can do stop and go, but unclear if it requires sDSU or unplugging DSU stop_and_go = True ret.wheelbase = 2.8194 # average of 109.8 and 112.2 in ret.steerRatio = 16.0 @@ -142,9 +142,7 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 3060. * CV.LB_TO_KG - elif candidate in (CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_ES_TSS2): - if candidate not in (CAR.LEXUS_ES,): # TODO: LEXUS_ES may have sng - stop_and_go = True + elif candidate in (CAR.LEXUS_ES, CAR.LEXUS_ES_TSS2): ret.wheelbase = 2.8702 ret.steerRatio = 16.0 # not optimized ret.tireStiffnessFactor = 0.444 # not optimized yet @@ -183,6 +181,12 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + elif candidate == CAR.LEXUS_LC_TSS2: + ret.wheelbase = 2.87 + ret.steerRatio = 13.0 + ret.tireStiffnessFactor = 0.444 # not optimized yet + ret.mass = 4500 * CV.LB_TO_KG + elif candidate == CAR.PRIUS_TSS2: ret.wheelbase = 2.70002 # from toyota online sepc. ret.steerRatio = 13.4 # True steerRatio from older prius @@ -221,17 +225,16 @@ class CarInterface(CarInterfaceBase): found_ecus = [fw.ecu for fw in car_fw] ret.enableDsu = len(found_ecus) > 0 and Ecu.dsu not in found_ecus and candidate not in (NO_DSU_CAR | UNSUPPORTED_DSU_CAR) \ and not (ret.flags & ToyotaFlags.SMART_DSU) - ret.enableGasInterceptor = 0x201 in fingerprint[0] # if the smartDSU is detected, openpilot can send ACC_CONTROL and the smartDSU will block it from the DSU or radar. # since we don't yet parse radar on TSS2/TSS-P radar-based ACC cars, gate longitudinal behind experimental toggle use_sdsu = bool(ret.flags & ToyotaFlags.SMART_DSU) if candidate in (RADAR_ACC_CAR | NO_DSU_CAR): - ret.experimentalLongitudinalAvailable = use_sdsu + ret.experimentalLongitudinalAvailable = use_sdsu or candidate in RADAR_ACC_CAR if not use_sdsu: # Disabling radar is only supported on TSS2 radar-ACC cars - if experimental_long and candidate in RADAR_ACC_CAR and False: # TODO: disabling radar isn't supported yet + if experimental_long and candidate in RADAR_ACC_CAR: ret.flags |= ToyotaFlags.DISABLE_RADAR.value else: use_sdsu = use_sdsu and experimental_long @@ -246,10 +249,14 @@ class CarInterface(CarInterfaceBase): # - TSS-P DSU-less cars w/ CAN filter installed (no radar parser yet) ret.openpilotLongitudinalControl = use_sdsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) or bool(ret.flags & ToyotaFlags.DISABLE_RADAR.value) ret.autoResumeSng = ret.openpilotLongitudinalControl and candidate in NO_STOP_TIMER_CAR + ret.enableGasInterceptor = 0x201 in fingerprint[0] and ret.openpilotLongitudinalControl if not ret.openpilotLongitudinalControl: ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL + if ret.enableGasInterceptor: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_GAS_INTERCEPTOR + # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else MIN_ACC_SPEED diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index ed0237c1be..e14e3e53a0 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -1,3 +1,8 @@ +from cereal import car + +SteerControlType = car.CarParams.SteerControlType + + def create_steer_command(packer, steer, steer_req): """Creates a CAN message for the Toyota Steer Command.""" @@ -9,15 +14,16 @@ def create_steer_command(packer, steer, steer_req): return packer.make_can_msg("STEERING_LKA", 0, values) -def create_lta_steer_command(packer, steer_angle, steer_req, frame, setme_x64): +def create_lta_steer_command(packer, steer_control_type, steer_angle, steer_req, frame, torque_wind_down): """Creates a CAN message for the Toyota LTA Steer Command.""" values = { "COUNTER": frame + 128, - "SETME_X1": 1, - "SETME_X3": 3, + "SETME_X1": 1, # suspected LTA feature availability + # 1 for TSS 2.5 cars, 3 for TSS 2.0. Send based on whether we're using LTA for lateral control + "SETME_X3": 1 if steer_control_type == SteerControlType.angle else 3, "PERCENTAGE": 100, - "SETME_X64": setme_x64, + "TORQUE_WIND_DOWN": torque_wind_down, "ANGLE": 0, "STEER_ANGLE_CMD": steer_angle, "STEER_REQUEST": steer_req, diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 4a1011982c..ed2b022f43 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -27,7 +27,8 @@ class CarControllerParams: # Assuming a steering ratio of 13.7: # Limit to ~2.0 m/s^3 up (7.5 deg/s), ~3.5 m/s^3 down (13 deg/s) at 75 mph # Worst case, the low speed limits will allow ~4.0 m/s^3 up (15 deg/s) and ~4.9 m/s^3 down (18 deg/s) at 75 mph, - # however the EPS has its own internal limits at all speeds which are less than that + # however the EPS has its own internal limits at all speeds which are less than that: + # Observed internal torque rate limit on TSS 2.5 Camry and RAV4 is ~1500 units/sec up and down when using LTA ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.3, 0.15]) ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.36, 0.26]) @@ -61,7 +62,6 @@ class CAR(StrEnum): COROLLA_TSS2 = "TOYOTA COROLLA TSS2 2019" HIGHLANDER = "TOYOTA HIGHLANDER 2017" HIGHLANDER_TSS2 = "TOYOTA HIGHLANDER 2020" - HIGHLANDERH = "TOYOTA HIGHLANDER HYBRID 2018" PRIUS = "TOYOTA PRIUS 2017" PRIUS_V = "TOYOTA PRIUS v 2017" PRIUS_TSS2 = "TOYOTA PRIUS TSS2 2021" @@ -76,15 +76,14 @@ class CAR(StrEnum): # Lexus LEXUS_CTH = "LEXUS CT HYBRID 2018" LEXUS_ES = "LEXUS ES 2018" - LEXUS_ESH = "LEXUS ES HYBRID 2018" LEXUS_ES_TSS2 = "LEXUS ES 2019" LEXUS_IS = "LEXUS IS 2018" LEXUS_IS_TSS2 = "LEXUS IS 2023" LEXUS_NX = "LEXUS NX 2018" LEXUS_NX_TSS2 = "LEXUS NX 2020" + LEXUS_LC_TSS2 = "LEXUS LC 2024" LEXUS_RC = "LEXUS RC 2020" LEXUS_RX = "LEXUS RX 2016" - LEXUS_RXH = "LEXUS RX HYBRID 2017" LEXUS_RX_TSS2 = "LEXUS RX 2020" LEXUS_GS_F = "LEXUS GS F 2016" @@ -146,12 +145,14 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ToyotaCarInfo("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5), ToyotaCarInfo("Lexus UX Hybrid 2019-23"), ], - CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), + CAR.HIGHLANDER: [ + ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), + ToyotaCarInfo("Toyota Highlander Hybrid 2017-19"), + ], CAR.HIGHLANDER_TSS2: [ ToyotaCarInfo("Toyota Highlander 2020-23"), ToyotaCarInfo("Toyota Highlander Hybrid 2020-23"), ], - CAR.HIGHLANDERH: ToyotaCarInfo("Toyota Highlander Hybrid 2017-19"), CAR.PRIUS: [ ToyotaCarInfo("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), ToyotaCarInfo("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), @@ -179,19 +180,21 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ToyotaCarInfo("Toyota RAV4 Hybrid 2022", video_link="https://youtu.be/U0nH9cnrFB0"), ], CAR.RAV4_TSS2_2023: [ - ToyotaCarInfo("Toyota RAV4 2023"), - ToyotaCarInfo("Toyota RAV4 Hybrid 2023"), + ToyotaCarInfo("Toyota RAV4 2023-24"), + ToyotaCarInfo("Toyota RAV4 Hybrid 2023-24"), ], CAR.MIRAI: ToyotaCarInfo("Toyota Mirai 2021"), CAR.SIENNA: ToyotaCarInfo("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED), # Lexus CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "Lexus Safety System+"), - CAR.LEXUS_ES: ToyotaCarInfo("Lexus ES 2017-18"), - CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18"), + CAR.LEXUS_ES: [ + ToyotaCarInfo("Lexus ES 2017-18"), + ToyotaCarInfo("Lexus ES Hybrid 2017-18"), + ], CAR.LEXUS_ES_TSS2: [ ToyotaCarInfo("Lexus ES 2019-24"), - ToyotaCarInfo("Lexus ES Hybrid 2019-23", video_link="https://youtu.be/BZ29osRVJeg?t=12"), + ToyotaCarInfo("Lexus ES Hybrid 2019-24", video_link="https://youtu.be/BZ29osRVJeg?t=12"), ], CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"), CAR.LEXUS_IS_TSS2: ToyotaCarInfo("Lexus IS 2022-23"), @@ -204,12 +207,12 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ToyotaCarInfo("Lexus NX 2020-21"), ToyotaCarInfo("Lexus NX Hybrid 2020-21"), ], + CAR.LEXUS_LC_TSS2: ToyotaCarInfo("Lexus LC 2024"), CAR.LEXUS_RC: ToyotaCarInfo("Lexus RC 2018-20"), CAR.LEXUS_RX: [ ToyotaCarInfo("Lexus RX 2016", "Lexus Safety System+"), ToyotaCarInfo("Lexus RX 2017-19"), - ], - CAR.LEXUS_RXH: [ + # Hybrid platforms ToyotaCarInfo("Lexus RX Hybrid 2016", "Lexus Safety System+"), ToyotaCarInfo("Lexus RX Hybrid 2017-19"), ], @@ -221,33 +224,32 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { # (addr, cars, bus, 1/freq*100, vl) STATIC_DSU_MSGS = [ - (0x128, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 1, 3, b'\xf4\x01\x90\x83\x00\x37'), - (0x128, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH), 1, 3, b'\x03\x00\x20\x00\x00\x52'), - (0x141, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, - CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), - (0x160, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, - CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), - (0x161, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.LEXUS_RX, CAR.PRIUS_V, CAR.LEXUS_ES), + (0x128, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 1, 3, b'\xf4\x01\x90\x83\x00\x37'), + (0x128, (CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 3, b'\x03\x00\x20\x00\x00\x52'), + (0x141, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, + CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), + (0x160, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, + CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.PRIUS_V), 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), - (0X161, (CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), - (0x283, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, - CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), - (0x2E6, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), - (0x2E7, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), - (0x33E, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), - (0x344, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, - CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), - (0x365, (CAR.PRIUS, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), - (0x365, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_RX, + (0X161, (CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), + (0x283, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, + CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), + (0x2E6, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), + (0x2E7, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x33E, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), + (0x344, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, + CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x365, (CAR.PRIUS, CAR.LEXUS_NX, CAR.HIGHLANDER), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), + (0x365, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), - (0x366, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), - (0x366, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), + (0x366, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.HIGHLANDER), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), + (0x366, (CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), - (0x366, (CAR.LEXUS_ES,), 0, 20, b'\x00\x95\x07\xfe\x08\x05\x00'), - (0x470, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, b'\x00\x00\x02\x7a'), - (0x470, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), - (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, - CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), + (0x470, (CAR.PRIUS, CAR.LEXUS_RX), 1, 100, b'\x00\x00\x02\x7a'), + (0x470, (CAR.HIGHLANDER, CAR.RAV4H, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), + (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, + CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), ] @@ -295,10 +297,10 @@ def get_platform_codes(fw_versions: List[bytes]) -> Dict[bytes, Set[bytes]]: return dict(codes) -def match_fw_to_car_fuzzy(live_fw_versions) -> Set[str]: +def match_fw_to_car_fuzzy(live_fw_versions, offline_fw_versions) -> Set[str]: candidates = set() - for candidate, fws in FW_VERSIONS.items(): + for candidate, fws in offline_fw_versions.items(): # Keep track of ECUs which pass all checks (platform codes, within sub-version range) valid_found_ecus = set() valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} @@ -348,13 +350,16 @@ FW_LEN_CODE = re.compile(b'^[\x01-\x03]') # highest seen is 3 chunks, 16 bytes FW_CHUNK_LEN = 16 # List of ECUs that are most unique across openpilot platforms -# TODO: use hybrid ECU, splits similar ICE and hybrid variants # - fwdCamera: describes actual features related to ADAS. For example, on the Avalon it describes # when TSS-P became standard, whether the car supports stop and go, and whether it's TSS2. # On the RAV4, it describes the move to the radar doing ACC, and the use of LTA for lane keeping. -# - abs: differentiates hybrid/ICE on most cars (Corolla TSS2 is an exception) +# Note that the platform codes & major versions do not describe features in plain text, only with +# matching against other seen FW versions in the database they can describe features. +# - fwdRadar: sanity check against fwdCamera, commonly shares a platform code. +# For example the RAV4 2022's new radar architecture is shown for both with platform code. +# - abs: differentiates hybrid/ICE on most cars (Corolla TSS2 is an exception, not used due to hybrid platform combination) # - eps: describes lateral API changes for the EPS, such as using LTA for lane keeping and rejecting LKA messages -PLATFORM_CODE_ECUS = [Ecu.fwdCamera, Ecu.abs, Ecu.eps] +PLATFORM_CODE_ECUS = (Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) # These platforms have at least one platform code for all ECUs shared with another platform. FUZZY_EXCLUDED_PLATFORMS: set[CAR] = set() @@ -394,8 +399,8 @@ FW_QUERY_CONFIG = FwQueryConfig( # FIXME: On some models, abs can sometimes be missing Ecu.abs: [CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_IS, CAR.ALPHARD_TSS2], # On some models, the engine can show on two different addresses - Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.CHR_TSS2, CAR.LEXUS_IS, CAR.LEXUS_RC, - CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.LEXUS_RX_TSS2], + Ecu.engine: [CAR.HIGHLANDER, CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.CHR_TSS2, CAR.LEXUS_IS, + CAR.LEXUS_RC, CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2], }, extra_ecus=[ # All known ECUs on a late-model Toyota vehicle not queried here: @@ -432,1642 +437,6 @@ FW_QUERY_CONFIG = FwQueryConfig( match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, ) -FW_VERSIONS = { - CAR.AVALON: { - (Ecu.abs, 0x7b0, None): [ - b'F152607060\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510701300\x00\x00\x00\x00', - b'881510705100\x00\x00\x00\x00', - b'881510705200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41051\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0701100\x00\x00\x00\x00', - b'8646F0703000\x00\x00\x00\x00', - ], - }, - CAR.AVALON_2019: { - (Ecu.abs, 0x7b0, None): [ - b'F152607140\x00\x00\x00\x00\x00\x00', - b'F152607171\x00\x00\x00\x00\x00\x00', - b'F152607110\x00\x00\x00\x00\x00\x00', - b'F152607180\x00\x00\x00\x00\x00\x00', - b'F152641040\x00\x00\x00\x00\x00\x00', - b'F152641061\x00\x00\x00\x00\x00\x00', - b'F152641050\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510703200\x00\x00\x00\x00', - b'881510704200\x00\x00\x00\x00', - b'881514107100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41080\x00\x00\x00\x00\x00\x00', - b'8965B07010\x00\x00\x00\x00\x00\x00', - b'8965B41090\x00\x00\x00\x00\x00\x00', - b'8965B41070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630725200\x00\x00\x00\x00', - b'\x01896630725300\x00\x00\x00\x00', - b'\x01896630735100\x00\x00\x00\x00', - b'\x01896630738000\x00\x00\x00\x00', - b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0702100\x00\x00\x00\x00', - ], - }, - CAR.AVALON_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F152607240\x00\x00\x00\x00\x00\x00', - b'\x01F152607250\x00\x00\x00\x00\x00\x00', - b'\x01F152607280\x00\x00\x00\x00\x00\x00', - b'F152641080\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41110\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630742000\x00\x00\x00\x00', - b'\x01896630743000\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.CAMRY: { - (Ecu.engine, 0x700, None): [ - b'\x018966306L3100\x00\x00\x00\x00', - b'\x018966306L4200\x00\x00\x00\x00', - b'\x018966306L5200\x00\x00\x00\x00', - b'\x018966306P8000\x00\x00\x00\x00', - b'\x018966306Q3100\x00\x00\x00\x00', - b'\x018966306Q4000\x00\x00\x00\x00', - b'\x018966306Q4100\x00\x00\x00\x00', - b'\x018966306Q4200\x00\x00\x00\x00', - b'\x018966333Q9200\x00\x00\x00\x00', - b'\x018966333P3100\x00\x00\x00\x00', - b'\x018966333P3200\x00\x00\x00\x00', - b'\x018966333P4200\x00\x00\x00\x00', - b'\x018966333P4300\x00\x00\x00\x00', - b'\x018966333P4400\x00\x00\x00\x00', - b'\x018966333P4500\x00\x00\x00\x00', - b'\x018966333P4700\x00\x00\x00\x00', - b'\x018966333P4900\x00\x00\x00\x00', - b'\x018966333Q6000\x00\x00\x00\x00', - b'\x018966333Q6200\x00\x00\x00\x00', - b'\x018966333Q6300\x00\x00\x00\x00', - b'\x018966333Q6500\x00\x00\x00\x00', - b'\x018966333W6000\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966333N1100\x00\x00\x00\x00', - b'\x018966333N4300\x00\x00\x00\x00', - b'\x018966333X0000\x00\x00\x00\x00', - b'\x018966333X4000\x00\x00\x00\x00', - b'\x01896633T16000\x00\x00\x00\x00', - b'\x018966306L9000\x00\x00\x00\x00', - b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0604100 ', - b'8821F0605200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'8821F0609100 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604200 ', - b'8821F0606200 ', - b'8821F0609000 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606210\x00\x00\x00\x00\x00\x00', - b'F152606230\x00\x00\x00\x00\x00\x00', - b'F152606270\x00\x00\x00\x00\x00\x00', - b'F152606290\x00\x00\x00\x00\x00\x00', - b'F152606410\x00\x00\x00\x00\x00\x00', - b'F152633540\x00\x00\x00\x00\x00\x00', - b'F152633A10\x00\x00\x00\x00\x00\x00', - b'F152633A20\x00\x00\x00\x00\x00\x00', - b'F152633214\x00\x00\x00\x00\x00\x00', - b'F152633660\x00\x00\x00\x00\x00\x00', - b'F152633712\x00\x00\x00\x00\x00\x00', - b'F152633713\x00\x00\x00\x00\x00\x00', - b'F152633B51\x00\x00\x00\x00\x00\x00', - b'F152633B60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33540\x00\x00\x00\x00\x00\x00', - b'8965B33542\x00\x00\x00\x00\x00\x00', - b'8965B33580\x00\x00\x00\x00\x00\x00', - b'8965B33581\x00\x00\x00\x00\x00\x00', - b'8965B33621\x00\x00\x00\x00\x00\x00', - b'8965B33550\x00\x00\x00\x00\x00\x00', - b'8965B33551\x00\x00\x00\x00\x00\x00', - b'8965B33611\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ # Same as 0x791 - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0604100 ', - b'8821F0605200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'8821F0609100 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604200 ', - b'8821F0606200 ', - b'8821F0609000 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0601200 ', - b'8646F0601300 ', - b'8646F0601400 ', - b'8646F0603400 ', - b'8646F0604100 ', - b'8646F0605000 ', - b'8646F0606000 ', - b'8646F0606100 ', - b'8646F0607100 ', - b'8646F0603500 ', - b'8646F0607000 ', - ], - }, - CAR.CAMRY_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B33630\x00\x00\x00\x00\x00\x00', - b'8965B33640\x00\x00\x00\x00\x00\x00', - b'8965B33650\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606370\x00\x00\x00\x00\x00\x00', - b'\x01F152606390\x00\x00\x00\x00\x00\x00', - b'\x01F152606400\x00\x00\x00\x00\x00\x00', - b'\x01F152606431\x00\x00\x00\x00\x00\x00', - b'F152633D00\x00\x00\x00\x00\x00\x00', - b'F152633D60\x00\x00\x00\x00\x00\x00', - b'F152633310\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x018966306Q5000\x00\x00\x00\x00', - b'\x018966306Q9000\x00\x00\x00\x00', - b'\x018966306R3000\x00\x00\x00\x00', - b'\x018966306R8000\x00\x00\x00\x00', - b'\x018966306T3100\x00\x00\x00\x00', - b'\x018966306T3200\x00\x00\x00\x00', - b'\x018966306T4000\x00\x00\x00\x00', - b'\x018966306T4100\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966306Q7000\x00\x00\x00\x00', - b'\x018966306T0000\x00\x00\x00\x00', - b'\x018966306V1000\x00\x00\x00\x00', - b'\x01896633T20000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F0602300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F3305200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F3305500\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.CHR: { - (Ecu.engine, 0x700, None): [ - b'\x01896631021100\x00\x00\x00\x00', - b'\x01896631017100\x00\x00\x00\x00', - b'\x01896631017200\x00\x00\x00\x00', - b'\x0189663F413100\x00\x00\x00\x00', - b'\x0189663F414100\x00\x00\x00\x00', - b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0189663F438000\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF405000 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152610020\x00\x00\x00\x00\x00\x00', - b'F152610153\x00\x00\x00\x00\x00\x00', - b'F152610210\x00\x00\x00\x00\x00\x00', - b'F1526F4034\x00\x00\x00\x00\x00\x00', - b'F1526F4044\x00\x00\x00\x00\x00\x00', - b'F1526F4073\x00\x00\x00\x00\x00\x00', - b'F1526F4121\x00\x00\x00\x00\x00\x00', - b'F1526F4122\x00\x00\x00\x00\x00\x00', - b'F152610012\x00\x00\x00\x00\x00\x00', - b'F152610013\x00\x00\x00\x00\x00\x00', - b'F152610014\x00\x00\x00\x00\x00\x00', - b'F152610040\x00\x00\x00\x00\x00\x00', - b'F152610190\x00\x00\x00\x00\x00\x00', - b'F152610200\x00\x00\x00\x00\x00\x00', - b'F152610220\x00\x00\x00\x00\x00\x00', - b'F152610230\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10011\x00\x00\x00\x00\x00\x00', - b'8965B10040\x00\x00\x00\x00\x00\x00', - b'8965B10070\x00\x00\x00\x00\x00\x00', - b'8965B10020\x00\x00\x00\x00\x00\x00', - b'8965B10050\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x0331036000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', - b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F0W01000 ', - b'8821FF401600 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - b'8821F0W01100 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF405000 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646FF401700 ', - b'8646FF401800 ', - b'8646FF404000 ', - b'8646FF406000 ', - b'8646FF407000 ', - b'8646FF402100 ', - b'8646FF407100 ', - ], - }, - CAR.CHR_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'F152610260\x00\x00\x00\x00\x00\x00', - b'F1526F4270\x00\x00\x00\x00\x00\x00', - b'F152610041\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10091\x00\x00\x00\x00\x00\x00', - b'8965B10110\x00\x00\x00\x00\x00\x00', - b'8965B10092\x00\x00\x00\x00\x00\x00', - b'8965B10111\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x0189663F459000\x00\x00\x00\x00', - b'\x0189663F438000\x00\x00\x00\x00', - b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821FF410200\x00\x00\x00\x00', - b'\x018821FF410300\x00\x00\x00\x00', - b'\x018821FF410500\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', - b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', - b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', - ], - }, - CAR.COROLLA: { - (Ecu.engine, 0x7e0, None): [ - b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510201100\x00\x00\x00\x00', - b'881510201200\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152602190\x00\x00\x00\x00\x00\x00', - b'F152602191\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B02181\x00\x00\x00\x00\x00\x00', - b'8965B02191\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0201101\x00\x00\x00\x00', - b'8646F0201200\x00\x00\x00\x00', - ], - }, - CAR.COROLLA_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630A22000\x00\x00\x00\x00', - b'\x01896630ZG2000\x00\x00\x00\x00', - b'\x01896630ZG5000\x00\x00\x00\x00', - b'\x01896630ZG5100\x00\x00\x00\x00', - b'\x01896630ZG5200\x00\x00\x00\x00', - b'\x01896630ZG5300\x00\x00\x00\x00', - b'\x01896630ZP1000\x00\x00\x00\x00', - b'\x01896630ZP2000\x00\x00\x00\x00', - b'\x01896630ZQ5000\x00\x00\x00\x00', - b'\x01896630ZU9000\x00\x00\x00\x00', - b'\x01896630ZX4000\x00\x00\x00\x00', - b'\x018966312L8000\x00\x00\x00\x00', - b'\x018966312M0000\x00\x00\x00\x00', - b'\x018966312M9000\x00\x00\x00\x00', - b'\x018966312P9000\x00\x00\x00\x00', - b'\x018966312P9100\x00\x00\x00\x00', - b'\x018966312P9200\x00\x00\x00\x00', - b'\x018966312P9300\x00\x00\x00\x00', - b'\x018966312Q2300\x00\x00\x00\x00', - b'\x018966312Q8000\x00\x00\x00\x00', - b'\x018966312R0000\x00\x00\x00\x00', - b'\x018966312R0100\x00\x00\x00\x00', - b'\x018966312R0200\x00\x00\x00\x00', - b'\x018966312R1000\x00\x00\x00\x00', - b'\x018966312R1100\x00\x00\x00\x00', - b'\x018966312R3100\x00\x00\x00\x00', - b'\x018966312S5000\x00\x00\x00\x00', - b'\x018966312S7000\x00\x00\x00\x00', - b'\x018966312W3000\x00\x00\x00\x00', - b'\x018966312W9000\x00\x00\x00\x00', - b'\x01896637644000\x00\x00\x00\x00', - b'\x01896630ZJ1000\x00\x00\x00\x00', - b'\x01896630ZU8000\x00\x00\x00\x00', - b'\x01896637621000\x00\x00\x00\x00', - b'\x01896637623000\x00\x00\x00\x00', - b'\x01896637624000\x00\x00\x00\x00', - b'\x01896637626000\x00\x00\x00\x00', - b'\x01896637639000\x00\x00\x00\x00', - b'\x01896637648000\x00\x00\x00\x00', - b'\x01896637643000\x00\x00\x00\x00', - b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', - b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x038966312T3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZN5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x018965B12350\x00\x00\x00\x00\x00\x00', - b'\x018965B12470\x00\x00\x00\x00\x00\x00', - b'\x018965B12490\x00\x00\x00\x00\x00\x00', - b'\x018965B12500\x00\x00\x00\x00\x00\x00', - b'\x018965B12520\x00\x00\x00\x00\x00\x00', - b'\x018965B12530\x00\x00\x00\x00\x00\x00', - b'\x018965B1255000\x00\x00\x00\x00', - b'8965B12361\x00\x00\x00\x00\x00\x00', - b'8965B16011\x00\x00\x00\x00\x00\x00', - b'8965B76012\x00\x00\x00\x00\x00\x00', - b'\x018965B12510\x00\x00\x00\x00\x00\x00', - b'\x018965B1256000\x00\x00\x00\x00', - b'8965B12451\x00\x00\x00\x00\x00\x00', - b'8965B16101\x00\x00\x00\x00\x00\x00', - b'8965B16170\x00\x00\x00\x00\x00\x00', - b'8965B76050\x00\x00\x00\x00\x00\x00', - b'8965B76091\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152602280\x00\x00\x00\x00\x00\x00', - b'\x01F152602560\x00\x00\x00\x00\x00\x00', - b'\x01F152602590\x00\x00\x00\x00\x00\x00', - b'\x01F152602650\x00\x00\x00\x00\x00\x00', - b'\x01F15260A010\x00\x00\x00\x00\x00\x00', - b'\x01F15260A050\x00\x00\x00\x00\x00\x00', - b'\x01F152612641\x00\x00\x00\x00\x00\x00', - b'\x01F152612651\x00\x00\x00\x00\x00\x00', - b'\x01F152612B10\x00\x00\x00\x00\x00\x00', - b'\x01F152612B51\x00\x00\x00\x00\x00\x00', - b'\x01F152612B60\x00\x00\x00\x00\x00\x00', - b'\x01F152612B61\x00\x00\x00\x00\x00\x00', - b'\x01F152612B62\x00\x00\x00\x00\x00\x00', - b'\x01F152612B70\x00\x00\x00\x00\x00\x00', - b'\x01F152612B71\x00\x00\x00\x00\x00\x00', - b'\x01F152612B81\x00\x00\x00\x00\x00\x00', - b'\x01F152612B90\x00\x00\x00\x00\x00\x00', - b'\x01F152612C00\x00\x00\x00\x00\x00\x00', - b'\x01F152612862\x00\x00\x00\x00\x00\x00', - b'\x01F152612B91\x00\x00\x00\x00\x00\x00', - b'\x01F15260A070\x00\x00\x00\x00\x00\x00', - b'\x01F152676250\x00\x00\x00\x00\x00\x00', - b'\x01F152602470\x00\x00\x00\x00\x00\x00', - b'F152612590\x00\x00\x00\x00\x00\x00', - b'F152612691\x00\x00\x00\x00\x00\x00', - b'F152612692\x00\x00\x00\x00\x00\x00', - b'F152612700\x00\x00\x00\x00\x00\x00', - b'F152612710\x00\x00\x00\x00\x00\x00', - b'F152612790\x00\x00\x00\x00\x00\x00', - b'F152612800\x00\x00\x00\x00\x00\x00', - b'F152612820\x00\x00\x00\x00\x00\x00', - b'F152612840\x00\x00\x00\x00\x00\x00', - b'F152612842\x00\x00\x00\x00\x00\x00', - b'F152612890\x00\x00\x00\x00\x00\x00', - b'F152612A00\x00\x00\x00\x00\x00\x00', - b'F152612A10\x00\x00\x00\x00\x00\x00', - b'F152612D00\x00\x00\x00\x00\x00\x00', - b'F152616011\x00\x00\x00\x00\x00\x00', - b'F152616060\x00\x00\x00\x00\x00\x00', - b'F152616030\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152676293\x00\x00\x00\x00\x00\x00', - b'F152676303\x00\x00\x00\x00\x00\x00', - b'F152676304\x00\x00\x00\x00\x00\x00', - b'F152676371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.HIGHLANDER: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E09000\x00\x00\x00\x00', - b'\x01896630E43000\x00\x00\x00\x00', - b'\x01896630E43100\x00\x00\x00\x00', - b'\x01896630E43200\x00\x00\x00\x00', - b'\x01896630E44200\x00\x00\x00\x00', - b'\x01896630E45000\x00\x00\x00\x00', - b'\x01896630E45100\x00\x00\x00\x00', - b'\x01896630E45200\x00\x00\x00\x00', - b'\x01896630E46000\x00\x00\x00\x00', - b'\x01896630E46200\x00\x00\x00\x00', - b'\x01896630E74000\x00\x00\x00\x00', - b'\x01896630E75000\x00\x00\x00\x00', - b'\x01896630E76000\x00\x00\x00\x00', - b'\x01896630E77000\x00\x00\x00\x00', - b'\x01896630E83000\x00\x00\x00\x00', - b'\x01896630E84000\x00\x00\x00\x00', - b'\x01896630E85000\x00\x00\x00\x00', - b'\x01896630E86000\x00\x00\x00\x00', - b'\x01896630E88000\x00\x00\x00\x00', - b'\x01896630EA0000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48140\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - b'8965B48210\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [b'F15260E011\x00\x00\x00\x00\x00\x00'], - (Ecu.dsu, 0x791, None): [ - b'881510E01100\x00\x00\x00\x00', - b'881510E01200\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0E01200\x00\x00\x00\x00', - b'8646F0E01300\x00\x00\x00\x00', - ], - }, - CAR.HIGHLANDERH: { - (Ecu.eps, 0x7a1, None): [ - b'8965B48160\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152648541\x00\x00\x00\x00\x00\x00', - b'F152648542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0E01200\x00\x00\x00\x00', - b'8646F0E01300\x00\x00\x00\x00', - ], - }, - CAR.HIGHLANDER_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B48241\x00\x00\x00\x00\x00\x00', - b'8965B48310\x00\x00\x00\x00\x00\x00', - b'8965B48320\x00\x00\x00\x00\x00\x00', - b'8965B48400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E051\x00\x00\x00\x00\x00\x00', - b'\x01F15260E061\x00\x00\x00\x00\x00\x00', - b'\x01F15260E110\x00\x00\x00\x00\x00\x00', - b'\x01F15260E170\x00\x00\x00\x00\x00\x00', - b'\x01F15260E05300\x00\x00\x00\x00', - b'\x01F15264872300\x00\x00\x00\x00', - b'\x01F15264872400\x00\x00\x00\x00', - b'\x01F15264872500\x00\x00\x00\x00', - b'\x01F15264872600\x00\x00\x00\x00', - b'\x01F15264872700\x00\x00\x00\x00', - b'\x01F15264873500\x00\x00\x00\x00', - b'\x01F152648C6300\x00\x00\x00\x00', - b'\x01F152648J4000\x00\x00\x00\x00', - b'\x01F152648J5000\x00\x00\x00\x00', - b'\x01F152648J6000\x00\x00\x00\x00', - b'\x01F152648J7000\x00\x00\x00\x00', - b'\x01F152648L5000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630E62100\x00\x00\x00\x00', - b'\x01896630E62200\x00\x00\x00\x00', - b'\x01896630E64100\x00\x00\x00\x00', - b'\x01896630E64200\x00\x00\x00\x00', - b'\x01896630E64400\x00\x00\x00\x00', - b'\x01896630EB1000\x00\x00\x00\x00', - b'\x01896630EB1100\x00\x00\x00\x00', - b'\x01896630EB1200\x00\x00\x00\x00', - b'\x01896630EB2000\x00\x00\x00\x00', - b'\x01896630EB2100\x00\x00\x00\x00', - b'\x01896630EB2200\x00\x00\x00\x00', - b'\x01896630EC4000\x00\x00\x00\x00', - b'\x01896630ED9000\x00\x00\x00\x00', - b'\x01896630ED9100\x00\x00\x00\x00', - b'\x01896630EE1000\x00\x00\x00\x00', - b'\x01896630EE1100\x00\x00\x00\x00', - b'\x01896630EG3000\x00\x00\x00\x00', - b'\x01896630EG5000\x00\x00\x00\x00', - b'\x01896630E67000\x00\x00\x00\x00', - b'\x01896630EA1000\x00\x00\x00\x00', - b'\x01896630EE4000\x00\x00\x00\x00', - b'\x01896630EE4100\x00\x00\x00\x00', - b'\x01896630EE5000\x00\x00\x00\x00', - b'\x01896630EE6000\x00\x00\x00\x00', - b'\x01896630EE7000\x00\x00\x00\x00', - b'\x01896630EF8000\x00\x00\x00\x00', - b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS: { - (Ecu.engine, 0x700, None): [ - b'\x018966353M7000\x00\x00\x00\x00', - b'\x018966353M7100\x00\x00\x00\x00', - b'\x018966353Q2000\x00\x00\x00\x00', - b'\x018966353Q2300\x00\x00\x00\x00', - b'\x018966353Q4000\x00\x00\x00\x00', - b'\x018966353R1100\x00\x00\x00\x00', - b'\x018966353R7100\x00\x00\x00\x00', - b'\x018966353R8100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152653300\x00\x00\x00\x00\x00\x00', - b'F152653301\x00\x00\x00\x00\x00\x00', - b'F152653310\x00\x00\x00\x00\x00\x00', - b'F152653330\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881515306200\x00\x00\x00\x00', - b'881515306400\x00\x00\x00\x00', - b'881515306500\x00\x00\x00\x00', - b'881515307400\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53270\x00\x00\x00\x00\x00\x00', - b'8965B53271\x00\x00\x00\x00\x00\x00', - b'8965B53280\x00\x00\x00\x00\x00\x00', - b'8965B53281\x00\x00\x00\x00\x00\x00', - b'8965B53311\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F5301101\x00\x00\x00\x00', - b'8646F5301200\x00\x00\x00\x00', - b'8646F5301300\x00\x00\x00\x00', - b'8646F5301400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966353S1000\x00\x00\x00\x00', - b'\x018966353S2000\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15265337200\x00\x00\x00\x00', - b'\x01F15265342000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53450\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.PRIUS: { - (Ecu.engine, 0x700, None): [ - b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', - b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47021\x00\x00\x00\x00\x00\x00', - b'8965B47022\x00\x00\x00\x00\x00\x00', - b'8965B47023\x00\x00\x00\x00\x00\x00', - b'8965B47050\x00\x00\x00\x00\x00\x00', - b'8965B47060\x00\x00\x00\x00\x00\x00', # This is the EPS with good angle sensor - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647290\x00\x00\x00\x00\x00\x00', - b'F152647300\x00\x00\x00\x00\x00\x00', - b'F152647310\x00\x00\x00\x00\x00\x00', - b'F152647414\x00\x00\x00\x00\x00\x00', - b'F152647415\x00\x00\x00\x00\x00\x00', - b'F152647416\x00\x00\x00\x00\x00\x00', - b'F152647417\x00\x00\x00\x00\x00\x00', - b'F152647470\x00\x00\x00\x00\x00\x00', - b'F152647490\x00\x00\x00\x00\x00\x00', - b'F152647682\x00\x00\x00\x00\x00\x00', - b'F152647683\x00\x00\x00\x00\x00\x00', - b'F152647684\x00\x00\x00\x00\x00\x00', - b'F152647862\x00\x00\x00\x00\x00\x00', - b'F152647863\x00\x00\x00\x00\x00\x00', - b'F152647864\x00\x00\x00\x00\x00\x00', - b'F152647865\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514702300\x00\x00\x00\x00', - b'881514702400\x00\x00\x00\x00', - b'881514703100\x00\x00\x00\x00', - b'881514704100\x00\x00\x00\x00', - b'881514706000\x00\x00\x00\x00', - b'881514706100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4701300\x00\x00\x00\x00', - b'8646F4702001\x00\x00\x00\x00', - b'8646F4702100\x00\x00\x00\x00', - b'8646F4702200\x00\x00\x00\x00', - b'8646F4705000\x00\x00\x00\x00', - b'8646F4705200\x00\x00\x00\x00', - ], - }, - CAR.PRIUS_V: { - (Ecu.abs, 0x7b0, None): [ - b'F152647280\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514705100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4703300\x00\x00\x00\x00', - ], - }, - CAR.RAV4: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42063\x00\x00\x00\x00\x00\x00', - b'8965B42073\x00\x00\x00\x00\x00\x00', - b'8965B42082\x00\x00\x00\x00\x00\x00', - b'8965B42083\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260R102\x00\x00\x00\x00\x00\x00', - b'F15260R103\x00\x00\x00\x00\x00\x00', - b'F152642493\x00\x00\x00\x00\x00\x00', - b'F152642492\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514201200\x00\x00\x00\x00', - b'881514201300\x00\x00\x00\x00', - b'881514201400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.RAV4H: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42102\x00\x00\x00\x00\x00\x00', - b'8965B42103\x00\x00\x00\x00\x00\x00', - b'8965B42112\x00\x00\x00\x00\x00\x00', - b'8965B42162\x00\x00\x00\x00\x00\x00', - b'8965B42163\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152642090\x00\x00\x00\x00\x00\x00', - b'F152642110\x00\x00\x00\x00\x00\x00', - b'F152642120\x00\x00\x00\x00\x00\x00', - b'F152642400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514202200\x00\x00\x00\x00', - b'881514202300\x00\x00\x00\x00', - b'881514202400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.RAV4_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630R58000\x00\x00\x00\x00', - b'\x01896630R58100\x00\x00\x00\x00', - b'\x018966342E2000\x00\x00\x00\x00', - b'\x018966342M8000\x00\x00\x00\x00', - b'\x018966342S9000\x00\x00\x00\x00', - b'\x018966342T1000\x00\x00\x00\x00', - b'\x018966342T6000\x00\x00\x00\x00', - b'\x018966342T9000\x00\x00\x00\x00', - b'\x018966342U4000\x00\x00\x00\x00', - b'\x018966342U4100\x00\x00\x00\x00', - b'\x018966342U5100\x00\x00\x00\x00', - b'\x018966342V0000\x00\x00\x00\x00', - b'\x018966342V3000\x00\x00\x00\x00', - b'\x018966342V3100\x00\x00\x00\x00', - b'\x018966342V3200\x00\x00\x00\x00', - b'\x01896634A05000\x00\x00\x00\x00', - b'\x01896634A19000\x00\x00\x00\x00', - b'\x01896634A19100\x00\x00\x00\x00', - b'\x01896634A20000\x00\x00\x00\x00', - b'\x01896634A20100\x00\x00\x00\x00', - b'\x01896634A22000\x00\x00\x00\x00', - b'\x01896634A22100\x00\x00\x00\x00', - b'\x01896634A30000\x00\x00\x00\x00', - b'\x01896634A44000\x00\x00\x00\x00', - b'\x01896634A45000\x00\x00\x00\x00', - b'\x01896634A46000\x00\x00\x00\x00', - b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', - b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x01896634A15000\x00\x00\x00\x00', - b'\x018966342M5000\x00\x00\x00\x00', - b'\x018966342W8000\x00\x00\x00\x00', - b'\x018966342X5000\x00\x00\x00\x00', - b'\x018966342X6000\x00\x00\x00\x00', - b'\x01896634A25000\x00\x00\x00\x00', - b'\x018966342W5000\x00\x00\x00\x00', - b'\x018966342W7000\x00\x00\x00\x00', - b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R210\x00\x00\x00\x00\x00\x00', - b'\x01F15260R220\x00\x00\x00\x00\x00\x00', - b'\x01F15260R290\x00\x00\x00\x00\x00\x00', - b'\x01F15260R300\x00\x00\x00\x00\x00\x00', - b'\x01F15260R302\x00\x00\x00\x00\x00\x00', - b'\x01F152642551\x00\x00\x00\x00\x00\x00', - b'\x01F152642561\x00\x00\x00\x00\x00\x00', - b'\x01F152642601\x00\x00\x00\x00\x00\x00', - b'\x01F152642700\x00\x00\x00\x00\x00\x00', - b'\x01F152642701\x00\x00\x00\x00\x00\x00', - b'\x01F152642710\x00\x00\x00\x00\x00\x00', - b'\x01F152642711\x00\x00\x00\x00\x00\x00', - b'\x01F152642750\x00\x00\x00\x00\x00\x00', - b'\x01F152642751\x00\x00\x00\x00\x00\x00', - b'\x01F15260R292\x00\x00\x00\x00\x00\x00', - b'F152642291\x00\x00\x00\x00\x00\x00', - b'F152642290\x00\x00\x00\x00\x00\x00', - b'F152642322\x00\x00\x00\x00\x00\x00', - b'F152642330\x00\x00\x00\x00\x00\x00', - b'F152642331\x00\x00\x00\x00\x00\x00', - b'F152642531\x00\x00\x00\x00\x00\x00', - b'F152642532\x00\x00\x00\x00\x00\x00', - b'F152642520\x00\x00\x00\x00\x00\x00', - b'F152642521\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152642541\x00\x00\x00\x00\x00\x00', - b'F152642542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42170\x00\x00\x00\x00\x00\x00', - b'8965B42171\x00\x00\x00\x00\x00\x00', - b'8965B42180\x00\x00\x00\x00\x00\x00', - b'8965B42181\x00\x00\x00\x00\x00\x00', - b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', - b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', - b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.RAV4_TSS2_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R350\x00\x00\x00\x00\x00\x00', - b'\x01F15260R361\x00\x00\x00\x00\x00\x00', - b'\x01F15264283100\x00\x00\x00\x00', - b'\x01F15264286200\x00\x00\x00\x00', - b'\x01F15264286100\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', - b'8965B42182\x00\x00\x00\x00\x00\x00', - b'8965B42172\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634AA0000\x00\x00\x00\x00', - b'\x01896634AA0100\x00\x00\x00\x00', - b'\x01896634AA1000\x00\x00\x00\x00', - b'\x01896634A88000\x00\x00\x00\x00', - b'\x01896634A89000\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634A02001\x00\x00\x00\x00', - b'\x01896634A03000\x00\x00\x00\x00', - b'\x01896634A08000\x00\x00\x00\x00', - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A62000\x00\x00\x00\x00', - b'\x01896634A62100\x00\x00\x00\x00', - b'\x01896634A63000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R01100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', - ], - }, - CAR.RAV4_TSS2_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R450\x00\x00\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264283300\x00\x00\x00\x00', - b'\x01F152642F1000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', - b'8965B42371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A88100\x00\x00\x00\x00', - b'\x01896634AJ2000\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AE1001\x00\x00\x00\x00', - b'\x01896634AF0000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R03100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', - b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', - ], - }, - CAR.SIENNA: { - (Ecu.engine, 0x700, None): [ - b'\x01896630832100\x00\x00\x00\x00', - b'\x01896630832200\x00\x00\x00\x00', - b'\x01896630838000\x00\x00\x00\x00', - b'\x01896630838100\x00\x00\x00\x00', - b'\x01896630842000\x00\x00\x00\x00', - b'\x01896630843000\x00\x00\x00\x00', - b'\x01896630851000\x00\x00\x00\x00', - b'\x01896630851100\x00\x00\x00\x00', - b'\x01896630851200\x00\x00\x00\x00', - b'\x01896630852000\x00\x00\x00\x00', - b'\x01896630852100\x00\x00\x00\x00', - b'\x01896630859000\x00\x00\x00\x00', - b'\x01896630860000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B45070\x00\x00\x00\x00\x00\x00', - b'8965B45080\x00\x00\x00\x00\x00\x00', - b'8965B45082\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152608130\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510801100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702200\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0801100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_CTH: { - (Ecu.dsu, 0x791, None): [ - b'881517601100\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152676144\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237635000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7601100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966306U6000\x00\x00\x00\x00', - b'\x018966333T5000\x00\x00\x00\x00', - b'\x018966333T5100\x00\x00\x00\x00', - b'\x018966333X6000\x00\x00\x00\x00', - b'\x01896633T07000\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - b'\x01896633T38000\x00\x00\x00\x00', - b'\x01896633T58000\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606281\x00\x00\x00\x00\x00\x00', - b'\x01F152606340\x00\x00\x00\x00\x00\x00', - b'\x01F152606461\x00\x00\x00\x00\x00\x00', - b'\x01F15260646200\x00\x00\x00\x00', - b'F152633423\x00\x00\x00\x00\x00\x00', - b'F152633680\x00\x00\x00\x00\x00\x00', - b'F152633681\x00\x00\x00\x00\x00\x00', - b'F152633F50\x00\x00\x00\x00\x00\x00', - b'F152633F51\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33252\x00\x00\x00\x00\x00\x00', - b'8965B33590\x00\x00\x00\x00\x00\x00', - b'8965B33690\x00\x00\x00\x00\x00\x00', - b'8965B33721\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES: { - (Ecu.engine, 0x7e0, None): [ - b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606202\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513309500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33502\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701200\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3302200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ESH: { - (Ecu.engine, 0x7e0, None): [ - b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152633171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513310400\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33512\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3302001\x00\x00\x00\x00', - b'8646F3302200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_GS_F: { - (Ecu.engine, 0x7E0, None): [ - b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152630700\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513016200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B30551\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3002100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX: { - (Ecu.engine, 0x700, None): [ - b'\x01896637850000\x00\x00\x00\x00', - b'\x01896637851000\x00\x00\x00\x00', - b'\x01896637852000\x00\x00\x00\x00', - b'\x01896637854000\x00\x00\x00\x00', - b'\x01896637878000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152678130\x00\x00\x00\x00\x00\x00', - b'F152678140\x00\x00\x00\x00\x00\x00', - b'F152678160\x00\x00\x00\x00\x00\x00', - b'F152678170\x00\x00\x00\x00\x00\x00', - b'F152678171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881517803100\x00\x00\x00\x00', - b'881517803300\x00\x00\x00\x00', - b'881517804300\x00\x00\x00\x00', - b'881517804100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78060\x00\x00\x00\x00\x00\x00', - b'8965B78080\x00\x00\x00\x00\x00\x00', - b'8965B78100\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7801100\x00\x00\x00\x00', - b'8646F7801300\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966378B2100\x00\x00\x00\x00', - b'\x018966378B3000\x00\x00\x00\x00', - b'\x018966378B4100\x00\x00\x00\x00', - b'\x018966378G2000\x00\x00\x00\x00', - b'\x018966378G3000\x00\x00\x00\x00', - b'\x018966378B2000\x00\x00\x00\x00', - b'\x018966378B3100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152678221\x00\x00\x00\x00\x00\x00', - b'F152678210\x00\x00\x00\x00\x00\x00', - b'F152678211\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78120\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b"\x018821F3301400\x00\x00\x00\x00", - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RC: { - (Ecu.engine, 0x700, None): [ - b'\x01896632461100\x00\x00\x00\x00', - b'\x01896632478200\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152624150\x00\x00\x00\x00\x00\x00', - b'F152624221\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881512404100\x00\x00\x00\x00', - b'881512407000\x00\x00\x00\x00', - b'881512409100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B24081\x00\x00\x00\x00\x00\x00', - b'8965B24240\x00\x00\x00\x00\x00\x00', - b'8965B24320\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F2401100\x00\x00\x00\x00', - b'8646F2401200\x00\x00\x00\x00', - b'8646F2402200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E36200\x00\x00\x00\x00', - b'\x01896630E36300\x00\x00\x00\x00', - b'\x01896630E37200\x00\x00\x00\x00', - b'\x01896630E37300\x00\x00\x00\x00', - b'\x01896630E41000\x00\x00\x00\x00', - b'\x01896630E41100\x00\x00\x00\x00', - b'\x01896630E41200\x00\x00\x00\x00', - b'\x01896630E41500\x00\x00\x00\x00', - b'\x01896630EA3100\x00\x00\x00\x00', - b'\x01896630EA3400\x00\x00\x00\x00', - b'\x01896630EA4100\x00\x00\x00\x00', - b'\x01896630EA4300\x00\x00\x00\x00', - b'\x01896630EA4400\x00\x00\x00\x00', - b'\x01896630EA6300\x00\x00\x00\x00', - b'\x018966348R1300\x00\x00\x00\x00', - b'\x018966348R8500\x00\x00\x00\x00', - b'\x018966348W1300\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152648472\x00\x00\x00\x00\x00\x00', - b'F152648473\x00\x00\x00\x00\x00\x00', - b'F152648492\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - b'F152648474\x00\x00\x00\x00\x00\x00', - b'F152648630\x00\x00\x00\x00\x00\x00', - b'F152648494\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514810300\x00\x00\x00\x00', - b'881514810500\x00\x00\x00\x00', - b'881514810700\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B0E011\x00\x00\x00\x00\x00\x00', - b'8965B0E012\x00\x00\x00\x00\x00\x00', - b'8965B48102\x00\x00\x00\x00\x00\x00', - b'8965B48111\x00\x00\x00\x00\x00\x00', - b'8965B48112\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701000\x00\x00\x00\x00', - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4801100\x00\x00\x00\x00', - b'8646F4801200\x00\x00\x00\x00', - b'8646F4802001\x00\x00\x00\x00', - b'8646F4802100\x00\x00\x00\x00', - b'8646F4802200\x00\x00\x00\x00', - b'8646F4809000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RXH: { - (Ecu.engine, 0x7e0, None): [ - b'\x02348J7000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Q4100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152648361\x00\x00\x00\x00\x00\x00', - b'F152648501\x00\x00\x00\x00\x00\x00', - b'F152648502\x00\x00\x00\x00\x00\x00', - b'F152648504\x00\x00\x00\x00\x00\x00', - b'F152648740\x00\x00\x00\x00\x00\x00', - b'F152648A30\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514811300\x00\x00\x00\x00', - b'881514811500\x00\x00\x00\x00', - b'881514811700\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B0E011\x00\x00\x00\x00\x00\x00', - b'8965B0E012\x00\x00\x00\x00\x00\x00', - b'8965B48111\x00\x00\x00\x00\x00\x00', - b'8965B48112\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701000\x00\x00\x00\x00', - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4801200\x00\x00\x00\x00', - b'8646F4802001\x00\x00\x00\x00', - b'8646F4802100\x00\x00\x00\x00', - b'8646F4802200\x00\x00\x00\x00', - b'8646F4809000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630EA9000\x00\x00\x00\x00', - b'\x01896630EB0000\x00\x00\x00\x00', - b'\x01896630EC9000\x00\x00\x00\x00', - b'\x01896630EC9100\x00\x00\x00\x00', - b'\x01896630ED0000\x00\x00\x00\x00', - b'\x01896630ED0100\x00\x00\x00\x00', - b'\x01896630ED6000\x00\x00\x00\x00', - b'\x018966348T8000\x00\x00\x00\x00', - b'\x018966348W5100\x00\x00\x00\x00', - b'\x018966348W9000\x00\x00\x00\x00', - b'\x01896634D12000\x00\x00\x00\x00', - b'\x01896634D12100\x00\x00\x00\x00', - b'\x01896634D43000\x00\x00\x00\x00', - b'\x01896634D44000\x00\x00\x00\x00', - b'\x018966348X0000\x00\x00\x00\x00', - b'\x01896630ED5000\x00\x00\x00\x00', - b'\x018966348R9200\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E031\x00\x00\x00\x00\x00\x00', - b'\x01F15260E041\x00\x00\x00\x00\x00\x00', - b'\x01F152648781\x00\x00\x00\x00\x00\x00', - b'\x01F152648801\x00\x00\x00\x00\x00\x00', - b'F152648831\x00\x00\x00\x00\x00\x00', - b'F152648891\x00\x00\x00\x00\x00\x00', - b'F152648D00\x00\x00\x00\x00\x00\x00', - b'F152648D60\x00\x00\x00\x00\x00\x00', - b'F152648811\x00\x00\x00\x00\x00\x00', - b'F152648C80\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48261\x00\x00\x00\x00\x00\x00', - b'8965B48271\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.PRIUS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647500\x00\x00\x00\x00\x00\x00', - b'F152647510\x00\x00\x00\x00\x00\x00', - b'F152647520\x00\x00\x00\x00\x00\x00', - b'F152647521\x00\x00\x00\x00\x00\x00', - b'F152647531\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.MIRAI: { - (Ecu.abs, 0x7D1, None): [b'\x01898A36203000\x00\x00\x00\x00',], - (Ecu.abs, 0x7B0, None): [ # a second ABS ECU - b'\x01F15266203200\x00\x00\x00\x00', - b'\x01F15266203500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7A1, None): [b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00',], - (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F6201200\x00\x00\x00\x00',], - (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',], - }, - CAR.ALPHARD_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B58040\x00\x00\x00\x00\x00\x00', - b'8965B58052\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152658341\x00\x00\x00\x00\x00\x00' - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, -} STEER_THRESHOLD = 100 @@ -2077,9 +446,9 @@ DBC = { CAR.PRIUS: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), CAR.PRIUS_V: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), CAR.COROLLA: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + CAR.LEXUS_LC_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.LEXUS_RC: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_RX: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - CAR.LEXUS_RXH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_RX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.CHR: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), CAR.CHR_TSS2: dbc_dict('toyota_nodsu_pt_generated', None), @@ -2087,7 +456,6 @@ DBC = { CAR.CAMRY_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.HIGHLANDER: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.HIGHLANDER_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.HIGHLANDERH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.AVALON: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.AVALON_2019: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), CAR.AVALON_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), @@ -2097,7 +465,6 @@ DBC = { CAR.COROLLA_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.LEXUS_ES: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), CAR.LEXUS_ES_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.LEXUS_ESH: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), CAR.SIENNA: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_IS: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_IS_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), @@ -2116,7 +483,8 @@ EPS_SCALE = defaultdict(lambda: 73, {CAR.PRIUS: 66, CAR.COROLLA: 88, CAR.LEXUS_I # Toyota/Lexus Safety Sense 2.0 and 2.5 TSS2_CAR = {CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.RAV4_TSS2_2023, CAR.COROLLA_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_RX_TSS2, CAR.HIGHLANDER_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.LEXUS_IS_TSS2, - CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2, CAR.CHR_TSS2} + CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.LEXUS_LC_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2, + CAR.CHR_TSS2} NO_DSU_CAR = TSS2_CAR | {CAR.CHR, CAR.CAMRY} @@ -2130,4 +498,4 @@ RADAR_ACC_CAR = {CAR.RAV4_TSS2_2022, CAR.RAV4_TSS2_2023, CAR.CHR_TSS2} ANGLE_CONTROL_CAR = {CAR.RAV4_TSS2_2023} # no resume button press required -NO_STOP_TIMER_CAR = TSS2_CAR | {CAR.PRIUS_V, CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_ESH} +NO_STOP_TIMER_CAR = TSS2_CAR | {CAR.PRIUS_V, CAR.RAV4H, CAR.HIGHLANDER, CAR.SIENNA} diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py index 28edf157ae..e668c35f7d 100755 --- a/selfdrive/car/vin.py +++ b/selfdrive/car/vin.py @@ -4,8 +4,8 @@ import re import cereal.messaging as messaging from panda.python.uds import get_rx_addr_for_tx_addr, FUNCTIONAL_ADDRS from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from openpilot.selfdrive.car.fw_query_definitions import StdQueries -from openpilot.system.swaglog import cloudlog +from openpilot.selfdrive.car.fw_query_definitions import STANDARD_VIN_ADDRS, StdQueries +from openpilot.common.swaglog import cloudlog VIN_UNKNOWN = "0" * 17 VIN_RE = "[A-HJ-NPR-Z0-9]{17}" @@ -15,33 +15,48 @@ def is_valid_vin(vin: str): return re.fullmatch(VIN_RE, vin) is not None -def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): - addrs = list(range(0x7e0, 0x7e8)) + list(range(0x18DA00F1, 0x18DB00F1, 0x100)) # addrs to process/wait for - valid_vin_addrs = [0x7e0, 0x7e2, 0x18da10f1, 0x18da0ef1] # engine, VMCU, 29-bit engine, PGM-FI +def get_vin(logcan, sendcan, buses, timeout=0.1, retry=2, debug=False): for i in range(retry): - for request, response in ((StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE), (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE)): - try: - query = IsoTpParallelQuery(sendcan, logcan, bus, addrs, [request, ], [response, ], functional_addrs=FUNCTIONAL_ADDRS, debug=debug) - results = query.get_data(timeout) - - for addr in valid_vin_addrs: - vin = results.get((addr, None)) - if vin is not None: - # Ford pads with null bytes - if len(vin) == 24: - vin = re.sub(b'\x00*$', b'', vin) - - # Honda Bosch response starts with a length, trim to correct length - if vin.startswith(b'\x11'): - vin = vin[1:18] - - return get_rx_addr_for_tx_addr(addr), vin.decode() - - cloudlog.error(f"vin query retry ({i+1}) ...") - except Exception: - cloudlog.exception("VIN query exception") - - return 0, VIN_UNKNOWN + for bus in buses: + for request, response, valid_buses, vin_addrs, functional_addrs, rx_offset in ( + (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, FUNCTIONAL_ADDRS, 0x8), + (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, FUNCTIONAL_ADDRS, 0x8), + (StdQueries.GM_VIN_REQUEST, StdQueries.GM_VIN_RESPONSE, (0,), [0x24b], None, 0x400), # Bolt fwdCamera + (StdQueries.KWP_VIN_REQUEST, StdQueries.KWP_VIN_RESPONSE, (0,), [0x797], None, 0x3), # Nissan Leaf VCM + ): + if bus not in valid_buses: + continue + + # When querying functional addresses, ideally we respond to everything that sends a first frame to avoid leaving the + # ECU in a temporary bad state. Note that we may not cover all ECUs and response offsets. TODO: query physical addrs + tx_addrs = vin_addrs + if functional_addrs is not None: + tx_addrs = [a for a in range(0x700, 0x800) if a != 0x7DF] + list(range(0x18DA00F1, 0x18DB00F1, 0x100)) + + try: + query = IsoTpParallelQuery(sendcan, logcan, bus, tx_addrs, [request, ], [response, ], response_offset=rx_offset, + functional_addrs=functional_addrs, debug=debug) + results = query.get_data(timeout) + + for addr in vin_addrs: + vin = results.get((addr, None)) + if vin is not None: + # Ford and Nissan pads with null bytes + if len(vin) in (19, 24): + vin = re.sub(b'\x00*$', b'', vin) + + # Honda Bosch response starts with a length, trim to correct length + if vin.startswith(b'\x11'): + vin = vin[1:18] + + cloudlog.error(f"got vin with {request=}") + return get_rx_addr_for_tx_addr(addr, rx_offset=rx_offset), bus, vin.decode() + except Exception: + cloudlog.exception("VIN query exception") + + cloudlog.error(f"vin query retry ({i+1}) ...") + + return -1, -1, VIN_UNKNOWN if __name__ == "__main__": @@ -59,5 +74,5 @@ if __name__ == "__main__": logcan = messaging.sub_sock('can') time.sleep(1) - vin_rx_addr, vin = get_vin(logcan, sendcan, args.bus, args.timeout, args.retry, debug=args.debug) - print(f'RX: {hex(vin_rx_addr)}, VIN: {vin}') + vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (args.bus,), args.timeout, args.retry, debug=args.debug) + print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index e7a7f2a998..0cee2c7fce 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -5,7 +5,7 @@ from openpilot.common.conversions import Conversions as CV from openpilot.common.realtime import DT_CTRL from openpilot.selfdrive.car import apply_driver_steer_torque_limits from openpilot.selfdrive.car.volkswagen import mqbcan, pqcan -from openpilot.selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams +from openpilot.selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams, VolkswagenFlags VisualAlert = car.CarControl.HUDControl.VisualAlert LongCtrlState = car.CarControl.Actuators.LongControlState @@ -65,13 +65,22 @@ class CarController: self.apply_steer_last = apply_steer can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hca_enabled)) + if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + # Pacify VW Emergency Assist driver inactivity detection by changing its view of driver steering input torque + # to the greatest of actual driver input or 2x openpilot's output (1x openpilot output is not enough to + # consistently reset inactivity detection on straight level roads). See commaai/openpilot#23274 for background. + ea_simulated_torque = clip(apply_steer * 2, -self.CCP.STEER_MAX, self.CCP.STEER_MAX) + if abs(CS.out.steeringTorque) > abs(ea_simulated_torque): + ea_simulated_torque = CS.out.steeringTorque + can_sends.append(self.CCS.create_eps_update(self.packer_pt, CANBUS.cam, CS.eps_stock_values, ea_simulated_torque)) + # **** Acceleration Controls ******************************************** # if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 stopping = actuators.longControlState == LongCtrlState.stopping - starting = actuators.longControlState == LongCtrlState.starting + starting = actuators.longControlState == LongCtrlState.pid and (CS.esp_hold_confirmation or CS.out.vEgo < self.CP.vEgoStopping) can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, acc_control, stopping, starting, CS.esp_hold_confirmation)) diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index cbe8918d48..25c5bc04bc 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -4,7 +4,7 @@ from openpilot.common.conversions import Conversions as CV from openpilot.selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser from openpilot.selfdrive.car.volkswagen.values import DBC, CANBUS, PQ_CARS, NetworkLocation, TransmissionType, GearShifter, \ - CarControllerParams + CarControllerParams, VolkswagenFlags class CarState(CarStateBase): @@ -14,6 +14,7 @@ class CarState(CarStateBase): self.button_states = {button.event_type: False for button in self.CCP.BUTTONS} self.esp_hold_confirmation = False self.upscale_lead_car_signal = False + self.eps_stock_values = False def create_button_events(self, pt_cp, buttons): button_events = [] @@ -59,6 +60,11 @@ class CarState(CarStateBase): ret.steerFaultPermanent = hca_status in ("DISABLED", "FAULT") ret.steerFaultTemporary = hca_status in ("INITIALIZING", "REJECTED") + # VW Emergency Assist status tracking and mitigation + self.eps_stock_values = pt_cp.vl["LH_EPS_03"] + if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + ret.carFaultedNonCritical = bool(cam_cp.vl["HCA_01"]["EA_Ruckfreigabe"]) or cam_cp.vl["HCA_01"]["EA_ACC_Sollstatus"] > 0 + # Update gas, brakes, and gearshift. ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 ret.gasPressed = ret.gas > 0 @@ -293,6 +299,11 @@ class CarState(CarStateBase): messages = [] + if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + messages += [ + ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not + ] + if CP.networkLocation == NetworkLocation.fwdCamera: messages += [ # sig_address, frequency diff --git a/selfdrive/car/volkswagen/fingerprints.py b/selfdrive/car/volkswagen/fingerprints.py new file mode 100644 index 0000000000..eab2bc0090 --- /dev/null +++ b/selfdrive/car/volkswagen/fingerprints.py @@ -0,0 +1,1164 @@ +from cereal import car +from openpilot.selfdrive.car.volkswagen.values import CAR + +Ecu = car.CarParams.Ecu + +# TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting + + +FW_VERSIONS = { + CAR.ARTEON_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x873G0906259AH\xf1\x890001', + b'\xf1\x873G0906259F \xf1\x890004', + b'\xf1\x873G0906259G \xf1\x890004', + b'\xf1\x873G0906259G \xf1\x890005', + b'\xf1\x873G0906259M \xf1\x890003', + b'\xf1\x873G0906259N \xf1\x890004', + b'\xf1\x873G0906259P \xf1\x890001', + b'\xf1\x875NA907115H \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158L \xf1\x893611', + b'\xf1\x870DL300014C \xf1\x893704', + b'\xf1\x870GC300011L \xf1\x891401', + b'\xf1\x870GC300014M \xf1\x892802', + b'\xf1\x870GC300019G \xf1\x892804', + b'\xf1\x870GC300040P \xf1\x891401', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', + b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', + b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', + b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', + b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', + b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.ATLAS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703H906026AA\xf1\x899970', + b'\xf1\x8703H906026AG\xf1\x899973', + b'\xf1\x8703H906026AJ\xf1\x890638', + b'\xf1\x8703H906026AJ\xf1\x891017', + b'\xf1\x8703H906026AT\xf1\x891922', + b'\xf1\x8703H906026BC\xf1\x892664', + b'\xf1\x8703H906026F \xf1\x896696', + b'\xf1\x8703H906026F \xf1\x899970', + b'\xf1\x8703H906026J \xf1\x896026', + b'\xf1\x8703H906026J \xf1\x899971', + b'\xf1\x8703H906026S \xf1\x896693', + b'\xf1\x8703H906026S \xf1\x899970', + b'\xf1\x873CN906259 \xf1\x890005', + b'\xf1\x873CN906259F \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158A \xf1\x893387', + b'\xf1\x8709G927158DR\xf1\x893536', + b'\xf1\x8709G927158DR\xf1\x893742', + b'\xf1\x8709G927158EN\xf1\x893691', + b'\xf1\x8709G927158F \xf1\x893489', + b'\xf1\x8709G927158FT\xf1\x893835', + b'\xf1\x8709G927158GL\xf1\x893939', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\x0e1914151912001103111122031200', + b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\x0e2214152212001105141122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e2214152212001105141122052900', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B60924A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572P \xf1\x890682', + ], + }, + CAR.CRAFTER_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056BP\xf1\x894729', + b'\xf1\x8704L906056EK\xf1\x896391', + b'\xf1\x8705L906023BC\xf1\x892688', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', + b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', + b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', + b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', + b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572J \xf1\x890156', + b'\xf1\x872Q0907572M \xf1\x890233', + ], + }, + CAR.GOLF_MK7: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906016A \xf1\x897697', + b'\xf1\x8704E906016AD\xf1\x895758', + b'\xf1\x8704E906016CE\xf1\x899096', + b'\xf1\x8704E906016CH\xf1\x899226', + b'\xf1\x8704E906016N \xf1\x899105', + b'\xf1\x8704E906023AG\xf1\x891726', + b'\xf1\x8704E906023BN\xf1\x894518', + b'\xf1\x8704E906024K \xf1\x896811', + b'\xf1\x8704E906024K \xf1\x899970', + b'\xf1\x8704E906027GR\xf1\x892394', + b'\xf1\x8704E906027HD\xf1\x892603', + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906027MA\xf1\x894958', + b'\xf1\x8704L906021DT\xf1\x895520', + b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906021N \xf1\x895518', + b'\xf1\x8704L906021N \xf1\x898138', + b'\xf1\x8704L906026BN\xf1\x891197', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906026NF\xf1\x899528', + b'\xf1\x8704L906056CL\xf1\x893823', + b'\xf1\x8704L906056CR\xf1\x895813', + b'\xf1\x8704L906056HE\xf1\x893758', + b'\xf1\x8704L906056HN\xf1\x896590', + b'\xf1\x8704L906056HT\xf1\x896591', + b'\xf1\x870EA906016A \xf1\x898343', + b'\xf1\x870EA906016E \xf1\x894219', + b'\xf1\x870EA906016F \xf1\x894238', + b'\xf1\x870EA906016F \xf1\x895002', + b'\xf1\x870EA906016Q \xf1\x895993', + b'\xf1\x870EA906016S \xf1\x897207', + b'\xf1\x875G0906259 \xf1\x890007', + b'\xf1\x875G0906259D \xf1\x890002', + b'\xf1\x875G0906259J \xf1\x890002', + b'\xf1\x875G0906259L \xf1\x890002', + b'\xf1\x875G0906259N \xf1\x890003', + b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x892313', + b'\xf1\x875G0906259T \xf1\x890003', + b'\xf1\x878V0906259H \xf1\x890002', + b'\xf1\x878V0906259J \xf1\x890003', + b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906259K \xf1\x890003', + b'\xf1\x878V0906259P \xf1\x890001', + b'\xf1\x878V0906259Q \xf1\x890002', + b'\xf1\x878V0906259R \xf1\x890002', + b'\xf1\x878V0906264F \xf1\x890003', + b'\xf1\x878V0906264L \xf1\x890002', + b'\xf1\x878V0906264M \xf1\x890001', + b'\xf1\x878V09C0BB01 \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927749AP\xf1\x892943', + b'\xf1\x8709S927158A \xf1\x893585', + b'\xf1\x870CW300040H \xf1\x890606', + b'\xf1\x870CW300041D \xf1\x891004', + b'\xf1\x870CW300041H \xf1\x891010', + b'\xf1\x870CW300042F \xf1\x891604', + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300043E \xf1\x891603', + b'\xf1\x870CW300044S \xf1\x894530', + b'\xf1\x870CW300044T \xf1\x895245', + b'\xf1\x870CW300045 \xf1\x894531', + b'\xf1\x870CW300047D \xf1\x895261', + b'\xf1\x870CW300047E \xf1\x895261', + b'\xf1\x870CW300048J \xf1\x890611', + b'\xf1\x870CW300049H \xf1\x890905', + b'\xf1\x870CW300050G \xf1\x891905', + b'\xf1\x870D9300012 \xf1\x894904', + b'\xf1\x870D9300012 \xf1\x894913', + b'\xf1\x870D9300012 \xf1\x894937', + b'\xf1\x870D9300012 \xf1\x895045', + b'\xf1\x870D9300012 \xf1\x895046', + b'\xf1\x870D9300014M \xf1\x895004', + b'\xf1\x870D9300014Q \xf1\x895006', + b'\xf1\x870D9300020J \xf1\x894902', + b'\xf1\x870D9300020Q \xf1\x895201', + b'\xf1\x870D9300020S \xf1\x895201', + b'\xf1\x870D9300040A \xf1\x893613', + b'\xf1\x870D9300040S \xf1\x894311', + b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041P \xf1\x894507', + b'\xf1\x870DD300045K \xf1\x891120', + b'\xf1\x870DD300046F \xf1\x891601', + b'\xf1\x870GC300012A \xf1\x891401', + b'\xf1\x870GC300012A \xf1\x891403', + b'\xf1\x870GC300014B \xf1\x892401', + b'\xf1\x870GC300014B \xf1\x892403', + b'\xf1\x870GC300014B \xf1\x892405', + b'\xf1\x870GC300020G \xf1\x892401', + b'\xf1\x870GC300020G \xf1\x892403', + b'\xf1\x870GC300020G \xf1\x892404', + b'\xf1\x870GC300020N \xf1\x892804', + b'\xf1\x870GC300043T \xf1\x899999', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', + b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', + b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', + b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', + b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', + b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', + b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', + b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', + b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', + b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', + b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', + b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', + b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', + b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', + b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', + b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', + b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572G \xf1\x890571', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890653', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.JETTA_MK7: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906024AK\xf1\x899937', + b'\xf1\x8704E906024AS\xf1\x899912', + b'\xf1\x8704E906024B \xf1\x895594', + b'\xf1\x8704E906024BC\xf1\x899971', + b'\xf1\x8704E906024BG\xf1\x891057', + b'\xf1\x8704E906024C \xf1\x899970', + b'\xf1\x8704E906024L \xf1\x895595', + b'\xf1\x8704E906024L \xf1\x899970', + b'\xf1\x8704E906027MS\xf1\x896223', + b'\xf1\x8705E906013DB\xf1\x893361', + b'\xf1\x875G0906259T \xf1\x890003', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158BQ\xf1\x893545', + b'\xf1\x8709S927158BS\xf1\x893642', + b'\xf1\x8709S927158BS\xf1\x893694', + b'\xf1\x8709S927158CK\xf1\x893770', + b'\xf1\x8709S927158JC\xf1\x894113', + b'\xf1\x8709S927158R \xf1\x893552', + b'\xf1\x8709S927158R \xf1\x893587', + b'\xf1\x870GC300020N \xf1\x892803', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1314171231313500314611011630169333463100', + b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314642011650169333463100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314643011650169333463100', + b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1311170031313300314240011150119333433100', + b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1319170031313300314240011550159333463100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314642021650169333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314643021650169333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1317171231313500314642023050309333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A10A11A1', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x000_A1080_OM', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A10A01A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A00642A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A10A01A1', + b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A10A11A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x875Q0907572N \xf1\x890681', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.PASSAT_MK8: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026E \xf1\x892114', + b'\xf1\x8704E906023AH\xf1\x893379', + b'\xf1\x8704E906023BM\xf1\x894522', + b'\xf1\x8704L906026DP\xf1\x891538', + b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x892012', + b'\xf1\x8704L906026GA\xf1\x892013', + b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x873G0906259 \xf1\x890004', + b'\xf1\x873G0906259B \xf1\x890002', + b'\xf1\x873G0906264 \xf1\x890004', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042H \xf1\x891601', + b'\xf1\x870CW300042H \xf1\x891607', + b'\xf1\x870CW300043H \xf1\x891601', + b'\xf1\x870CW300048R \xf1\x890610', + b'\xf1\x870D9300013A \xf1\x894905', + b'\xf1\x870D9300014L \xf1\x895002', + b'\xf1\x870D9300018C \xf1\x895297', + b'\xf1\x870D9300041A \xf1\x894801', + b'\xf1\x870D9300042H \xf1\x894901', + b'\xf1\x870DD300045T \xf1\x891601', + b'\xf1\x870DD300046H \xf1\x891601', + b'\xf1\x870DL300011H \xf1\x895201', + b'\xf1\x870GC300042H \xf1\x891404', + b'\xf1\x870GC300043 \xf1\x892301', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', + b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', + b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012416612124111', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', + b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', + b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001344701311442900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011111200631145171716121691132111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521B00606A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516B00501A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00603A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00703A1', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572A \xf1\x890126', + b'\xf1\x873Q0907572A \xf1\x890130', + b'\xf1\x873Q0907572B \xf1\x890192', + b'\xf1\x873Q0907572B \xf1\x890194', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x873Q0907572C \xf1\x890196', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.PASSAT_NMS: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8706K906016C \xf1\x899609', + b'\xf1\x8706K906016E \xf1\x899830', + b'\xf1\x8706K906016G \xf1\x891124', + b'\xf1\x8706K906071BJ\xf1\x894891', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158AB\xf1\x893318', + b'\xf1\x8709G927158BD\xf1\x893121', + b'\xf1\x8709G927158DK\xf1\x893594', + b'\xf1\x8709G927158FQ\xf1\x893745', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x87561959655 \xf1\x890210\xf1\x82\x1212121111113000102011--121012--101312', + b'\xf1\x87561959655C \xf1\x890508\xf1\x82\x1215141111121100314919--153015--304831', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x87561907567A \xf1\x890132', + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0152', + ], + }, + CAR.POLO_MK6: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025H \xf1\x895177', + b'\xf1\x8705C906032J \xf1\x891702', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042D \xf1\x891612', + b'\xf1\x870CW300050D \xf1\x891908', + b'\xf1\x870CW300051G \xf1\x891909', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144M \xf1\x896041', + b'\xf1\x872Q2909144AB\xf1\x896050', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.SHARAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906016HE\xf1\x894635', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', + ], + }, + CAR.TAOS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906025CK\xf1\x892228', + b'\xf1\x8704E906027NJ\xf1\x891445', + b'\xf1\x8704E906027NP\xf1\x891286', + b'\xf1\x8705E906013BD\xf1\x892496', + b'\xf1\x8705E906013E \xf1\x891624', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158EM\xf1\x893812', + b'\xf1\x8709S927158BL\xf1\x893791', + b'\xf1\x8709S927158CR\xf1\x893924', + b'\xf1\x8709S927158DN\xf1\x893946', + b'\xf1\x8709S927158FF\xf1\x893876', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', + b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.TCROSS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025AK\xf1\x897053', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300050E \xf1\x891903', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1212130411110411--04041104141311152H14', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.TIGUAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026D \xf1\x893680', + b'\xf1\x8704E906024AP\xf1\x891461', + b'\xf1\x8704E906027NB\xf1\x899504', + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906027G \xf1\x899893', + b'\xf1\x8705E906018BS\xf1\x890914', + b'\xf1\x875N0906259 \xf1\x890002', + b'\xf1\x875NA906259H \xf1\x890002', + b'\xf1\x875NA907115E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890005', + b'\xf1\x875NA907115J \xf1\x890002', + b'\xf1\x875NA907115K \xf1\x890004', + b'\xf1\x8783A907115 \xf1\x890007', + b'\xf1\x8783A907115B \xf1\x890005', + b'\xf1\x8783A907115F \xf1\x890002', + b'\xf1\x8783A907115G \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890002', + b'\xf1\x8783A907115Q \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158DT\xf1\x893698', + b'\xf1\x8709G927158FM\xf1\x893757', + b'\xf1\x8709G927158GC\xf1\x893821', + b'\xf1\x8709G927158GD\xf1\x893820', + b'\xf1\x8709G927158GM\xf1\x893936', + b'\xf1\x8709G927158GN\xf1\x893938', + b'\xf1\x8709G927158HB\xf1\x894069', + b'\xf1\x870D9300043 \xf1\x895202', + b'\xf1\x870DD300046K \xf1\x892302', + b'\xf1\x870DL300011N \xf1\x892001', + b'\xf1\x870DL300011N \xf1\x892012', + b'\xf1\x870DL300012M \xf1\x892107', + b'\xf1\x870DL300012P \xf1\x892103', + b'\xf1\x870DL300013A \xf1\x893005', + b'\xf1\x870DL300013G \xf1\x892119', + b'\xf1\x870DL300013G \xf1\x892120', + b'\xf1\x870DL300014C \xf1\x893703', + b'\xf1\x870GC300013P \xf1\x892401', + b'\xf1\x870GC300046Q \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1316143231313500314617011730179333423100', + b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1316143231313500314617011730179333423100', + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x1331310031333334313132573732379333313100', + b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1331310031333334313132013730379333423100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1316143231313500314641011750179333423100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1312110031333300314240013750379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1312110031333300314240583752379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333336313140013950399333423100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', + b'\xf1\x875Q0959655CD\xf1\x890421\xf1\x82\x13123112313333003145406F6154619333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6050705', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6070705', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6017A00', + b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A60634A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002RA60A2ROM', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60804A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60804A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572J \xf1\x890156', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572Q \xf1\x890342', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.TOURAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906026HM\xf1\x893017', + b'\xf1\x8705E906018CQ\xf1\x890808', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041E \xf1\x891005', + b'\xf1\x870CW300051M \xf1\x891926', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x13363500213533353141324C4732479333313100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x873Q0907572C \xf1\x890195', + ], + }, + CAR.TRANSPORTER_T61: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056AG\xf1\x899970', + b'\xf1\x8704L906056AL\xf1\x899970', + b'\xf1\x8704L906057AP\xf1\x891186', + b'\xf1\x8704L906057N \xf1\x890413', + b'\xf1\x8705L906023E \xf1\x891352', + b'\xf1\x8705L906023MR\xf1\x892582', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870BT300012E \xf1\x893105', + b'\xf1\x870BT300012G \xf1\x893102', + b'\xf1\x870BT300046R \xf1\x893102', + b'\xf1\x870DV300012B \xf1\x893701', + b'\xf1\x870DV300012B \xf1\x893702', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', + b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', + b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', + b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', + b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.TROC_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018AT\xf1\x899640', + b'\xf1\x8705E906018CK\xf1\x890863', + b'\xf1\x8705E906018P \xf1\x896020', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041S \xf1\x891615', + b'\xf1\x870CW300050J \xf1\x891911', + b'\xf1\x870CW300051M \xf1\x891925', + b'\xf1\x870CW300051M \xf1\x891928', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', + b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', + b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.AUDI_A3_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906023AN\xf1\x893695', + b'\xf1\x8704E906023AR\xf1\x893440', + b'\xf1\x8704E906023BL\xf1\x895190', + b'\xf1\x8704E906027CJ\xf1\x897798', + b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x875G0906259A \xf1\x890004', + b'\xf1\x875G0906259D \xf1\x890002', + b'\xf1\x875G0906259L \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x878V0906259E \xf1\x890001', + b'\xf1\x878V0906259F \xf1\x890002', + b'\xf1\x878V0906259H \xf1\x890002', + b'\xf1\x878V0906259J \xf1\x890002', + b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906264B \xf1\x890003', + b'\xf1\x878V0907115B \xf1\x890007', + b'\xf1\x878V0907404A \xf1\x890005', + b'\xf1\x878V0907404G \xf1\x890005', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300044T \xf1\x895245', + b'\xf1\x870CW300048 \xf1\x895201', + b'\xf1\x870D9300012 \xf1\x894912', + b'\xf1\x870D9300012 \xf1\x894931', + b'\xf1\x870D9300012K \xf1\x894513', + b'\xf1\x870D9300012L \xf1\x894521', + b'\xf1\x870D9300013B \xf1\x894902', + b'\xf1\x870D9300013B \xf1\x894931', + b'\xf1\x870D9300041N \xf1\x894512', + b'\xf1\x870D9300043T \xf1\x899699', + b'\xf1\x870DD300046 \xf1\x891604', + b'\xf1\x870DD300046A \xf1\x891602', + b'\xf1\x870DD300046F \xf1\x891602', + b'\xf1\x870DD300046G \xf1\x891601', + b'\xf1\x870DL300012E \xf1\x892012', + b'\xf1\x870DL300012H \xf1\x892112', + b'\xf1\x870GC300011 \xf1\x890403', + b'\xf1\x870GC300013M \xf1\x892402', + b'\xf1\x870GC300042J \xf1\x891402', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\x111111001111111206110412111321139114', + b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', + b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', + b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--171115141112221291163221', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221', + b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112110004110411111421149114', + b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112111104110411111521159114', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', + b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566G0HA14A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521G0G809A1', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00303A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00803A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516G00804A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516G00804A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521G00807A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', + b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572G \xf1\x890571', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572P \xf1\x890682', + ], + }, + CAR.AUDI_Q2_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027JT\xf1\x894145', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041F \xf1\x891006', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572M \xf1\x890233', + ], + }, + CAR.AUDI_Q3_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018N \xf1\x899970', + b'\xf1\x8705L906022M \xf1\x890901', + b'\xf1\x8783A906259 \xf1\x890001', + b'\xf1\x8783A906259 \xf1\x890005', + b'\xf1\x8783A906259C \xf1\x890002', + b'\xf1\x8783A906259D \xf1\x890001', + b'\xf1\x8783A906259F \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158CN\xf1\x893608', + b'\xf1\x8709G927158FL\xf1\x893758', + b'\xf1\x8709G927158GG\xf1\x893825', + b'\xf1\x8709G927158GP\xf1\x893937', + b'\xf1\x870GC300045D \xf1\x892802', + b'\xf1\x870GC300046F \xf1\x892701', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', + b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218A219321532111', + b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', + b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', + b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60733A1', + b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SEAT_ATECA_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027KA\xf1\x893749', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870D9300014S \xf1\x895202', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1212001211001305121211052900', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571N60511A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572M \xf1\x890233', + ], + }, + CAR.SEAT_LEON_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906021EL\xf1\x897542', + b'\xf1\x8704L906026BP\xf1\x891198', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906056CR\xf1\x892181', + b'\xf1\x8704L906056CR\xf1\x892797', + b'\xf1\x8705E906018AS\xf1\x899596', + b'\xf1\x878V0906264H \xf1\x890005', + b'\xf1\x878V0907115E \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041D \xf1\x891004', + b'\xf1\x870CW300041G \xf1\x891003', + b'\xf1\x870CW300050J \xf1\x891908', + b'\xf1\x870D9300042M \xf1\x895016', + b'\xf1\x870GC300043A \xf1\x892304', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e1312001313001305171311052900', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521N01342A1', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511N01805A0', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N05808A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.SKODA_FABIA_MK4: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018CF\xf1\x891905', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300051M \xf1\x891936', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144S \xf1\x896042', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + ], + }, + CAR.SKODA_KAMIQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705C906032M \xf1\x891333', + b'\xf1\x8705E906013CK\xf1\x892540', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020 \xf1\x891906', + b'\xf1\x870CW300020T \xf1\x892204', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x122221042111042121040404042E2711152H14', + b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144AB\xf1\x896050', + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_KAROQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906013H \xf1\x892407', + b'\xf1\x8705E906018P \xf1\x895472', + b'\xf1\x8705E906018P \xf1\x896020', + b'\xf1\x8705L906022BS\xf1\x890913', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020T \xf1\x892202', + b'\xf1\x870CW300041S \xf1\x891615', + b'\xf1\x870GC300014L \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1213001211001101131122012100', + b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_KODIAQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027DD\xf1\x893123', + b'\xf1\x8704E906027LD\xf1\x893433', + b'\xf1\x8704E906027NB\xf1\x896517', + b'\xf1\x8704E906027NB\xf1\x899504', + b'\xf1\x8704L906026DE\xf1\x895418', + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906026HT\xf1\x893617', + b'\xf1\x8705E906018DJ\xf1\x890915', + b'\xf1\x8705E906018DJ\xf1\x891903', + b'\xf1\x875NA906259E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890005', + b'\xf1\x8783A907115E \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870D9300014S \xf1\x895201', + b'\xf1\x870D9300043 \xf1\x895202', + b'\xf1\x870DL300011N \xf1\x892014', + b'\xf1\x870DL300012M \xf1\x892107', + b'\xf1\x870DL300012N \xf1\x892110', + b'\xf1\x870DL300013G \xf1\x892119', + b'\xf1\x870GC300014N \xf1\x892801', + b'\xf1\x870GC300019H \xf1\x892806', + b'\xf1\x870GC300046Q \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', + b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', + b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', + b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572Q \xf1\x890342', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_OCTAVIA_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025L \xf1\x896198', + b'\xf1\x8704E906016ER\xf1\x895823', + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906027MH\xf1\x894786', + b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906026BS\xf1\x891541', + b'\xf1\x875G0906259C \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041L \xf1\x891601', + b'\xf1\x870CW300041N \xf1\x891605', + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300043P \xf1\x891605', + b'\xf1\x870D9300041C \xf1\x894936', + b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041J \xf1\x894902', + b'\xf1\x870D9300041P \xf1\x894507', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655AK\xf1\x890306\xf1\x82\r31210031210021033733310331', + b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', + b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01513A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', + b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.SKODA_SCALA_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025AK\xf1\x897053', + b'\xf1\x8705C906032M \xf1\x892365', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020 \xf1\x891907', + b'\xf1\x870CW300050 \xf1\x891709', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', + b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x12111104111104112104040404111111112H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144AB\xf1\x896050', + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.SKODA_SUPERB_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027BS\xf1\x892887', + b'\xf1\x8704E906027BT\xf1\x899042', + b'\xf1\x8704L906026ET\xf1\x891343', + b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x891196', + b'\xf1\x8704L906026KA\xf1\x896014', + b'\xf1\x8704L906026KB\xf1\x894071', + b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x8704L906026MT\xf1\x893076', + b'\xf1\x8705L906022BK\xf1\x899971', + b'\xf1\x873G0906259 \xf1\x890004', + b'\xf1\x873G0906259B \xf1\x890002', + b'\xf1\x873G0906259L \xf1\x890003', + b'\xf1\x873G0906264A \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042H \xf1\x891601', + b'\xf1\x870CW300043B \xf1\x891603', + b'\xf1\x870CW300049Q \xf1\x890906', + b'\xf1\x870D9300011T \xf1\x894801', + b'\xf1\x870D9300012 \xf1\x894940', + b'\xf1\x870D9300013A \xf1\x894905', + b'\xf1\x870D9300014K \xf1\x895006', + b'\xf1\x870D9300041H \xf1\x894905', + b'\xf1\x870D9300042M \xf1\x895013', + b'\xf1\x870D9300043F \xf1\x895202', + b'\xf1\x870GC300013K \xf1\x892403', + b'\xf1\x870GC300014M \xf1\x892801', + b'\xf1\x870GC300019G \xf1\x892803', + b'\xf1\x870GC300043 \xf1\x892301', + b'\xf1\x870GC300046D \xf1\x892402', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', + b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121118112231292221111', + b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', + b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', + b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', + b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1333310031313100313152015351539331423100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060700', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572B \xf1\x890192', + b'\xf1\x873Q0907572B \xf1\x890194', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, +} diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index d5377453c1..710e779d0a 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -3,7 +3,7 @@ from panda import Panda from openpilot.common.conversions import Conversions as CV from openpilot.selfdrive.car import get_safety_config from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.volkswagen.values import CAR, PQ_CARS, CANBUS, NetworkLocation, TransmissionType, GearShifter +from openpilot.selfdrive.car.volkswagen.values import CAR, PQ_CARS, CANBUS, NetworkLocation, TransmissionType, GearShifter, VolkswagenFlags ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName @@ -67,6 +67,9 @@ class CarInterface(CarInterfaceBase): else: ret.networkLocation = NetworkLocation.fwdCamera + if 0x126 in fingerprint[2]: # HCA_01 + ret.flags |= VolkswagenFlags.STOCK_HCA_PRESENT.value + # Global lateral tuning defaults, can be overridden per-vehicle ret.steerActuatorDelay = 0.1 @@ -90,11 +93,9 @@ class CarInterface(CarInterfaceBase): ret.pcmCruise = not ret.openpilotLongitudinalControl ret.stoppingControl = True - ret.startingState = True - ret.startAccel = 1.0 ret.stopAccel = -0.55 - ret.vEgoStarting = 1.0 - ret.vEgoStopping = 1.0 + ret.vEgoStarting = 0.1 + ret.vEgoStopping = 0.5 ret.longitudinalTuning.kpV = [0.1] ret.longitudinalTuning.kiV = [0.0] diff --git a/selfdrive/car/volkswagen/mqbcan.py b/selfdrive/car/volkswagen/mqbcan.py index 849d99592f..787c7de530 100644 --- a/selfdrive/car/volkswagen/mqbcan.py +++ b/selfdrive/car/volkswagen/mqbcan.py @@ -10,6 +10,24 @@ def create_steering_control(packer, bus, apply_steer, lkas_enabled): return packer.make_can_msg("HCA_01", bus, values) +def create_eps_update(packer, bus, eps_stock_values, ea_simulated_torque): + values = {s: eps_stock_values[s] for s in [ + "COUNTER", # Sync counter value to EPS output + "EPS_Lenkungstyp", # EPS rack type + "EPS_Berechneter_LW", # Absolute raw steering angle + "EPS_VZ_BLW", # Raw steering angle sign + "EPS_HCA_Status", # EPS HCA control status + ]} + + values.update({ + # Absolute driver torque input and sign, with EA inactivity mitigation + "EPS_Lenkmoment": abs(ea_simulated_torque), + "EPS_VZ_Lenkmoment": 1 if ea_simulated_torque < 0 else 0, + }) + + return packer.make_can_msg("LH_EPS_03", bus, values) + + def create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pressed, hud_alert, hud_control): values = {} if len(ldw_stock_values): @@ -94,7 +112,7 @@ def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_cont acc_hold_type = 0 acc_07_values = { - "ACC_Anhalteweg": 0.75 if stopping else 20.46, # Distance to stop (stopping coordinator handles terminal roll-out) + "ACC_Anhalteweg": 0.3 if stopping else 20.46, # Distance to stop (stopping coordinator handles terminal roll-out) "ACC_Freilauf_Info": 2 if acc_enabled else 0, "ACC_Folgebeschl": 3.02, # Not using secondary controller accel unless and until we understand its impact "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index c8e6daaef8..35cb3607ec 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -1,6 +1,6 @@ from collections import defaultdict, namedtuple from dataclasses import dataclass, field -from enum import Enum, StrEnum +from enum import Enum, IntFlag, StrEnum from typing import Dict, List, Union from cereal import car @@ -109,6 +109,10 @@ class CANBUS: cam = 2 +class VolkswagenFlags(IntFlag): + STOCK_HCA_PRESENT = 1 + + # Check the 7th and 8th characters of the VIN before adding a new CAR. If the # chassis code is already listed below, don't add a new CAR, just add to the # FW_VERSIONS for that existing CAR. @@ -219,8 +223,8 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { VWCarInfo("Volkswagen Golf SportsVan 2015-20"), ], CAR.JETTA_MK7: [ - VWCarInfo("Volkswagen Jetta 2018-22"), - VWCarInfo("Volkswagen Jetta GLI 2021-22"), + VWCarInfo("Volkswagen Jetta 2018-24"), + VWCarInfo("Volkswagen Jetta GLI 2021-24"), ], CAR.PASSAT_MK8: [ VWCarInfo("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]), @@ -239,7 +243,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022-23"), CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0]), CAR.TIGUAN_MK2: [ - VWCarInfo("Volkswagen Tiguan 2018-23"), + VWCarInfo("Volkswagen Tiguan 2018-24"), VWCarInfo("Volkswagen Tiguan eHybrid 2021-23"), ], CAR.TOURAN_MK2: VWCarInfo("Volkswagen Touran 2016-23"), @@ -303,1138 +307,3 @@ FW_QUERY_CONFIG = FwQueryConfig( ), ], ) - -FW_VERSIONS = { - CAR.ARTEON_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x873G0906259AH\xf1\x890001', - b'\xf1\x873G0906259F \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890005', - b'\xf1\x873G0906259M \xf1\x890003', - b'\xf1\x873G0906259N \xf1\x890004', - b'\xf1\x873G0906259P \xf1\x890001', - b'\xf1\x875NA907115H \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158L \xf1\x893611', - b'\xf1\x870DL300014C \xf1\x893704', - b'\xf1\x870GC300011L \xf1\x891401', - b'\xf1\x870GC300014M \xf1\x892802', - b'\xf1\x870GC300019G \xf1\x892804', - b'\xf1\x870GC300040P \xf1\x891401', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', - b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', - b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', - b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.ATLAS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703H906026AA\xf1\x899970', - b'\xf1\x8703H906026AG\xf1\x899973', - b'\xf1\x8703H906026AJ\xf1\x890638', - b'\xf1\x8703H906026AJ\xf1\x891017', - b'\xf1\x8703H906026AT\xf1\x891922', - b'\xf1\x8703H906026BC\xf1\x892664', - b'\xf1\x8703H906026F \xf1\x896696', - b'\xf1\x8703H906026F \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x896026', - b'\xf1\x8703H906026J \xf1\x899971', - b'\xf1\x8703H906026S \xf1\x896693', - b'\xf1\x8703H906026S \xf1\x899970', - b'\xf1\x873CN906259 \xf1\x890005', - b'\xf1\x873CN906259F \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158A \xf1\x893387', - b'\xf1\x8709G927158DR\xf1\x893536', - b'\xf1\x8709G927158DR\xf1\x893742', - b'\xf1\x8709G927158EN\xf1\x893691', - b'\xf1\x8709G927158F \xf1\x893489', - b'\xf1\x8709G927158FT\xf1\x893835', - b'\xf1\x8709G927158GL\xf1\x893939', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\0161914151912001103111122031200', - b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\0162214152212001105141122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\0162214152212001105141122052900', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\00571B60924A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - ], - }, - CAR.CRAFTER_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056BP\xf1\x894729', - b'\xf1\x8704L906056EK\xf1\x896391', - b'\xf1\x8705L906023BC\xf1\x892688', - ], - # Only current upstreamed vehicle has a manual transmission - #(Ecu.transmission, 0x7e1, None): [ - #], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', - b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', - b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', - b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', - b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.GOLF_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906016A \xf1\x897697', - b'\xf1\x8704E906016N \xf1\x899105', - b'\xf1\x8704E906016AD\xf1\x895758', - b'\xf1\x8704E906016CE\xf1\x899096', - b'\xf1\x8704E906016CH\xf1\x899226', - b'\xf1\x8704E906023AG\xf1\x891726', - b'\xf1\x8704E906023BN\xf1\x894518', - b'\xf1\x8704E906024K \xf1\x896811', - b'\xf1\x8704E906027GR\xf1\x892394', - b'\xf1\x8704E906027HD\xf1\x892603', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MA\xf1\x894958', - b'\xf1\x8704L906021DT\xf1\x895520', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021N \xf1\x895518', - b'\xf1\x8704L906021N \xf1\x898138', - b'\xf1\x8704L906026BN\xf1\x891197', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026NF\xf1\x899528', - b'\xf1\x8704L906056CL\xf1\x893823', - b'\xf1\x8704L906056CR\xf1\x895813', - b'\xf1\x8704L906056HE\xf1\x893758', - b'\xf1\x8704L906056HN\xf1\x896590', - b'\xf1\x8704L906056HT\xf1\x896591', - b'\xf1\x870EA906016A \xf1\x898343', - b'\xf1\x870EA906016E \xf1\x894219', - b'\xf1\x870EA906016F \xf1\x894238', - b'\xf1\x870EA906016F \xf1\x895002', - b'\xf1\x870EA906016Q \xf1\x895993', - b'\xf1\x870EA906016S \xf1\x897207', - b'\xf1\x875G0906259 \xf1\x890007', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259J \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259N \xf1\x890003', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x892313', - b'\xf1\x875G0906259T \xf1\x890003', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890003', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906259K \xf1\x890003', - b'\xf1\x878V0906259P \xf1\x890001', - b'\xf1\x878V0906259Q \xf1\x890002', - b'\xf1\x878V0906259R \xf1\x890002', - b'\xf1\x878V0906264F \xf1\x890003', - b'\xf1\x878V0906264L \xf1\x890002', - b'\xf1\x878V0906264M \xf1\x890001', - b'\xf1\x878V09C0BB01 \xf1\x890001', - b'\xf1\x8704E906024K \xf1\x899970', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927749AP\xf1\x892943', - b'\xf1\x8709S927158A \xf1\x893585', - b'\xf1\x870CW300040H \xf1\x890606', - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041H \xf1\x891010', - b'\xf1\x870CW300042F \xf1\x891604', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043E \xf1\x891603', - b'\xf1\x870CW300044S \xf1\x894530', - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300045 \xf1\x894531', - b'\xf1\x870CW300047D \xf1\x895261', - b'\xf1\x870CW300047E \xf1\x895261', - b'\xf1\x870CW300048J \xf1\x890611', - b'\xf1\x870CW300049H \xf1\x890905', - b'\xf1\x870CW300050G \xf1\x891905', - b'\xf1\x870D9300012 \xf1\x894904', - b'\xf1\x870D9300012 \xf1\x894913', - b'\xf1\x870D9300012 \xf1\x894937', - b'\xf1\x870D9300012 \xf1\x895045', - b'\xf1\x870D9300012 \xf1\x895046', - b'\xf1\x870D9300014M \xf1\x895004', - b'\xf1\x870D9300014Q \xf1\x895006', - b'\xf1\x870D9300020J \xf1\x894902', - b'\xf1\x870D9300020Q \xf1\x895201', - b'\xf1\x870D9300020S \xf1\x895201', - b'\xf1\x870D9300040A \xf1\x893613', - b'\xf1\x870D9300040S \xf1\x894311', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041P \xf1\x894507', - b'\xf1\x870DD300045K \xf1\x891120', - b'\xf1\x870DD300046F \xf1\x891601', - b'\xf1\x870GC300012A \xf1\x891401', - b'\xf1\x870GC300012A \xf1\x891403', - b'\xf1\x870GC300014B \xf1\x892401', - b'\xf1\x870GC300014B \xf1\x892403', - b'\xf1\x870GC300014B \xf1\x892405', - b'\xf1\x870GC300020G \xf1\x892401', - b'\xf1\x870GC300020G \xf1\x892403', - b'\xf1\x870GC300020G \xf1\x892404', - b'\xf1\x870GC300020N \xf1\x892804', - b'\xf1\x870GC300043T \xf1\x899999', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', - b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', - b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', - b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', - b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', - b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', - b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', - b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', - b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890653', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.JETTA_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906024AK\xf1\x899937', - b'\xf1\x8704E906024AS\xf1\x899912', - b'\xf1\x8704E906024BC\xf1\x899971', - b'\xf1\x8704E906024BG\xf1\x891057', - b'\xf1\x8704E906024B \xf1\x895594', - b'\xf1\x8704E906024C \xf1\x899970', - b'\xf1\x8704E906024L \xf1\x895595', - b'\xf1\x8704E906024L \xf1\x899970', - b'\xf1\x8704E906027MS\xf1\x896223', - b'\xf1\x875G0906259T \xf1\x890003', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158BQ\xf1\x893545', - b'\xf1\x8709S927158BS\xf1\x893642', - b'\xf1\x8709S927158BS\xf1\x893694', - b'\xf1\x8709S927158CK\xf1\x893770', - b'\xf1\x8709S927158R \xf1\x893552', - b'\xf1\x8709S927158R \xf1\x893587', - b'\xf1\x870GC300020N \xf1\x892803', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\02314171231313500314611011630169333463100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02314171231313500314642011650169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02314171231313500314643011650169333463100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\02311170031313300314240011150119333433100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\02319170031313300314240011550159333463100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314643021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314642021650169333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A10A11A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\00521A10A01A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A00642A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A10A01A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\00571A10A11A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907572N \xf1\x890681', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.PASSAT_MK8: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026E \xf1\x892114', - b'\xf1\x8704E906023AH\xf1\x893379', - b'\xf1\x8704E906023BM\xf1\x894522', - b'\xf1\x8704L906026DP\xf1\x891538', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x892012', - b'\xf1\x8704L906026GA\xf1\x892013', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906264 \xf1\x890004', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300043H \xf1\x891601', - b'\xf1\x870CW300048R \xf1\x890610', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014L \xf1\x895002', - b'\xf1\x870D9300041A \xf1\x894801', - b'\xf1\x870DD300045T \xf1\x891601', - b'\xf1\x870DD300046H \xf1\x891601', - b'\xf1\x870DL300011H \xf1\x895201', - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300042H \xf1\x891607', - b'\xf1\x870GC300042H \xf1\x891404', - b'\xf1\x870D9300018C \xf1\x895297', - b'\xf1\x870GC300043 \xf1\x892301', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', - b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\0165915005914001344701311442900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\02315120011111200631145171716121691132111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521B00606A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\00516B00501A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521B00703A1', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572A \xf1\x890126', - b'\xf1\x873Q0907572A \xf1\x890130', - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x873Q0907572C \xf1\x890196', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.PASSAT_NMS: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8706K906016C \xf1\x899609', - b'\xf1\x8706K906016E \xf1\x899830', - b'\xf1\x8706K906016G \xf1\x891124', - b'\xf1\x8706K906071BJ\xf1\x894891', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158AB\xf1\x893318', - b'\xf1\x8709G927158BD\xf1\x893121', - b'\xf1\x8709G927158DK\xf1\x893594', - b'\xf1\x8709G927158FQ\xf1\x893745', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x87561959655 \xf1\x890210\xf1\x82\02212121111113000102011--121012--101312', - b'\xf1\x87561959655C \xf1\x890508\xf1\x82\02215141111121100314919--153015--304831', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x87561907567A \xf1\x890132', - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\00152', - ], - }, - CAR.POLO_MK6: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025H \xf1\x895177', - b'\xf1\x8705C906032J \xf1\x891702', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042D \xf1\x891612', - b'\xf1\x870CW300050D \xf1\x891908', - b'\xf1\x870CW300051G \xf1\x891909', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - b'\xf1\x872Q2909144AB\xf1\x896050', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.SHARAN_MK2: { - # TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906016HE\xf1\x894635', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', - ], - }, - CAR.TAOS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027NJ\xf1\x891445', - b'\xf1\x8704E906027NP\xf1\x891286', - b'\xf1\x8705E906013BD\xf1\x892496', - b'\xf1\x8705E906013E \xf1\x891624', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158EM\xf1\x893812', - b'\xf1\x8709S927158BL\xf1\x893791', - b'\xf1\x8709S927158DN\xf1\x893946', - b'\xf1\x8709S927158FF\xf1\x893876', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', - b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.TCROSS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300050E \xf1\x891903', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\02212130411110411--04041104141311152H14', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.TIGUAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026D \xf1\x893680', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906027G \xf1\x899893', - b'\xf1\x8705E906018BS\xf1\x890914', - b'\xf1\x875N0906259 \xf1\x890002', - b'\xf1\x875NA906259H \xf1\x890002', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x875NA907115J \xf1\x890002', - b'\xf1\x8783A907115B \xf1\x890005', - b'\xf1\x8783A907115F \xf1\x890002', - b'\xf1\x8783A907115G \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890002', - b'\xf1\x8704E906024AP\xf1\x891461', - b'\xf1\x8783A907115 \xf1\x890007', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158DT\xf1\x893698', - b'\xf1\x8709G927158FM\xf1\x893757', - b'\xf1\x8709G927158GC\xf1\x893821', - b'\xf1\x8709G927158GD\xf1\x893820', - b'\xf1\x8709G927158GM\xf1\x893936', - b'\xf1\x8709G927158GN\xf1\x893938', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DL300011N \xf1\x892001', - b'\xf1\x870DL300011N \xf1\x892012', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012P \xf1\x892103', - b'\xf1\x870DL300013A \xf1\x893005', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870DL300013G \xf1\x892120', - b'\xf1\x870DL300014C \xf1\x893703', - b'\xf1\x870DD300046K \xf1\x892302', - b'\xf1\x870GC300013P \xf1\x892401', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\02331310031333334313132573732379333313100', - b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1331310031333334313132013730379333423100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02316143231313500314641011750179333423100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1312110031333300314240013750379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02312110031333300314240583752379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02331310031333336313140013950399333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100', - b'\xf1\x875Q0959655CD\xf1\x890421\xf1\x82\x13123112313333003145406F6154619333613100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1316143231313500314617011730179333423100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6050705', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600', - b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\00571A60634A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A60804A1', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002RA60A2ROM', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6017A00', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60804A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.TOURAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906026HM\xf1\x893017', - b'\xf1\x8705E906018CQ\xf1\x890808', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041E \xf1\x891005', - b'\xf1\x870CW300051M \xf1\x891926', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\023363500213533353141324C4732479333313100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.TRANSPORTER_T61: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056AG\xf1\x899970', - b'\xf1\x8704L906056AL\xf1\x899970', - b'\xf1\x8704L906057AP\xf1\x891186', - b'\xf1\x8704L906057N \xf1\x890413', - b'\xf1\x8705L906023E \xf1\x891352', - b'\xf1\x8705L906023MR\xf1\x892582', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870BT300012G \xf1\x893102', - b'\xf1\x870BT300012E \xf1\x893105', - b'\xf1\x870BT300046R \xf1\x893102', - b'\xf1\x870DV300012B \xf1\x893701', - b'\xf1\x870DV300012B \xf1\x893702', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', - b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', - b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', - b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.TROC_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018AT\xf1\x899640', - b'\xf1\x8705E906018CK\xf1\x890863', - b'\xf1\x8705E906018P \xf1\x896020', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300050J \xf1\x891911', - b'\xf1\x870CW300051M \xf1\x891925', - b'\xf1\x870CW300051M \xf1\x891928', - b'\xf1\x870CW300041S \xf1\x891615', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', - b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.AUDI_A3_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906023AN\xf1\x893695', - b'\xf1\x8704E906023AR\xf1\x893440', - b'\xf1\x8704E906023BL\xf1\x895190', - b'\xf1\x8704E906027CJ\xf1\x897798', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x875G0906259A \xf1\x890004', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x878V0906259E \xf1\x890001', - b'\xf1\x878V0906259F \xf1\x890002', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890002', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906264B \xf1\x890003', - b'\xf1\x878V0907115B \xf1\x890007', - b'\xf1\x878V0907404A \xf1\x890005', - b'\xf1\x878V0907404G \xf1\x890005', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300048 \xf1\x895201', - b'\xf1\x870D9300012 \xf1\x894912', - b'\xf1\x870D9300012 \xf1\x894931', - b'\xf1\x870D9300012L \xf1\x894521', - b'\xf1\x870D9300012K \xf1\x894513', - b'\xf1\x870D9300013B \xf1\x894902', - b'\xf1\x870D9300013B \xf1\x894931', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300043T \xf1\x899699', - b'\xf1\x870DD300046 \xf1\x891604', - b'\xf1\x870DD300046A \xf1\x891602', - b'\xf1\x870DD300046F \xf1\x891602', - b'\xf1\x870DD300046G \xf1\x891601', - b'\xf1\x870DL300012E \xf1\x892012', - b'\xf1\x870DL300012H \xf1\x892112', - b'\xf1\x870GC300011 \xf1\x890403', - b'\xf1\x870GC300013M \xf1\x892402', - b'\xf1\x870GC300042J \xf1\x891402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\0211111001111111206110412111321139114', - b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', - b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', - b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112110004110411111421149114', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112111104110411111521159114', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\00566G0HA14A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00303A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00803A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\00516G00804A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521G00807A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', - b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572P \xf1\x890682', - ], - }, - CAR.AUDI_Q2_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027JT\xf1\x894145', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041F \xf1\x891006', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.AUDI_Q3_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018N \xf1\x899970', - b'\xf1\x8705L906022M \xf1\x890901', - b'\xf1\x8783A906259 \xf1\x890001', - b'\xf1\x8783A906259 \xf1\x890005', - b'\xf1\x8783A906259C \xf1\x890002', - b'\xf1\x8783A906259D \xf1\x890001', - b'\xf1\x8783A906259F \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158CN\xf1\x893608', - b'\xf1\x8709G927158FL\xf1\x893758', - b'\xf1\x8709G927158GG\xf1\x893825', - b'\xf1\x8709G927158GP\xf1\x893937', - b'\xf1\x870GC300045D \xf1\x892802', - b'\xf1\x870GC300046F \xf1\x892701', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218A219321532111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60733A1', - b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SEAT_ATECA_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027KA\xf1\x893749', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870D9300014S \xf1\x895202', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\0161212001211001305121211052900', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\00571N60511A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.SEAT_LEON_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906021EL\xf1\x897542', - b'\xf1\x8704L906026BP\xf1\x891198', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906056CR\xf1\x892181', - b'\xf1\x8704L906056CR\xf1\x892797', - b'\xf1\x8705E906018AS\xf1\x899596', - b'\xf1\x878V0906264H \xf1\x890005', - b'\xf1\x878V0907115E \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041G \xf1\x891003', - b'\xf1\x870CW300050J \xf1\x891908', - b'\xf1\x870D9300042M \xf1\x895016', - b'\xf1\x870GC300043A \xf1\x892304', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\0161312001313001305171311052900', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521N01342A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00511N01805A0', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521N05808A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\00101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_FABIA_MK4: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018CF\xf1\x891905', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300051M \xf1\x891936', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144S \xf1\x896042', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.SKODA_KAMIQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705C906032M \xf1\x891333', - b'\xf1\x8705E906013CK\xf1\x892540', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020 \xf1\x891906', - b'\xf1\x870CW300020T \xf1\x892204', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\0222221042111042121040404042E2711152H14', - b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - b'\xf1\x872Q1909144AB\xf1\x896050', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.SKODA_KAROQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906013H \xf1\x892407', - b'\xf1\x8705E906018P \xf1\x895472', - b'\xf1\x8705E906018P \xf1\x896020', - b'\xf1\x8705L906022BS\xf1\x890913', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020T \xf1\x892202', - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870GC300014L \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\0161213001211001101131122012100', - b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KODIAQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027DD\xf1\x893123', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704E906027NB\xf1\x896517', - b'\xf1\x8704L906026DE\xf1\x895418', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906026HT\xf1\x893617', - b'\xf1\x8783A907115E \xf1\x890001', - b'\xf1\x8705E906018DJ\xf1\x890915', - b'\xf1\x8705E906018DJ\xf1\x891903', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x875NA906259E \xf1\x890003', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DL300011N \xf1\x892014', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012N \xf1\x892110', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870GC300014N \xf1\x892801', - b'\xf1\x870GC300019H \xf1\x892806', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', - b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', - b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - ], - }, - CAR.SKODA_OCTAVIA_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025L \xf1\x896198', - b'\xf1\x8704E906016ER\xf1\x895823', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MH\xf1\x894786', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026BS\xf1\x891541', - b'\xf1\x875G0906259C \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041L \xf1\x891601', - b'\xf1\x870CW300041N \xf1\x891605', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043P \xf1\x891605', - b'\xf1\x870D9300041C \xf1\x894936', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041J \xf1\x894902', - b'\xf1\x870D9300041P \xf1\x894507', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', - b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\0163221003221002105755331052100', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\00566A01513A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\00521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', - b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\00101', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_SCALA_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - b'\xf1\x8705C906032M \xf1\x892365', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020 \xf1\x891907', - b'\xf1\x870CW300050 \xf1\x891709', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\022111104111104112104040404111111112H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - b'\xf1\x872Q1909144AB\xf1\x896050', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.SKODA_SUPERB_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027BS\xf1\x892887', - b'\xf1\x8704E906027BT\xf1\x899042', - b'\xf1\x8704L906026ET\xf1\x891343', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x891196', - b'\xf1\x8704L906026KA\xf1\x896014', - b'\xf1\x8704L906026KB\xf1\x894071', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8704L906026MT\xf1\x893076', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906259L \xf1\x890003', - b'\xf1\x873G0906264A \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300043B \xf1\x891603', - b'\xf1\x870CW300049Q \xf1\x890906', - b'\xf1\x870D9300011T \xf1\x894801', - b'\xf1\x870D9300012 \xf1\x894940', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014K \xf1\x895006', - b'\xf1\x870D9300041H \xf1\x894905', - b'\xf1\x870D9300042M \xf1\x895013', - b'\xf1\x870D9300043F \xf1\x895202', - b'\xf1\x870GC300013K \xf1\x892403', - b'\xf1\x870GC300014M \xf1\x892801', - b'\xf1\x870GC300019G \xf1\x892803', - b'\xf1\x870GC300043 \xf1\x892301', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\022111200111121001121118112231292221111', - b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\022111200111121001121110012211292221111', - b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', - b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\02331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\00563UZ060700', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, -} diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 19ce407932..bf2b14c1da 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -2,36 +2,42 @@ import os import math import time +import threading from typing import SupportsFloat -from cereal import car, log -from openpilot.common.numpy_fast import clip -from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL -from openpilot.common.profiler import Profiler -from openpilot.common.params import Params, put_nonblocking, put_bool_nonblocking import cereal.messaging as messaging + +from cereal import car, log from cereal.visionipc import VisionIpcClient, VisionStreamType -from openpilot.common.conversions import Conversions as CV + from panda import ALTERNATIVE_EXPERIENCE -from openpilot.system.swaglog import cloudlog -from openpilot.system.version import is_release_branch, get_short_branch + +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import clip +from openpilot.common.params import Params +from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL +from openpilot.common.swaglog import cloudlog + from openpilot.selfdrive.boardd.boardd import can_list_to_can_capnp from openpilot.selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can -from openpilot.selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET -from openpilot.selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert +from openpilot.selfdrive.controls.lib.drive_helpers import VCruiseHelper, clip_curvature +from openpilot.selfdrive.controls.lib.events import Events, ET from openpilot.selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED -from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle, STEER_ANGLE_SATURATION_THRESHOLD from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque -from openpilot.selfdrive.controls.lib.events import Events, ET -from openpilot.selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert +from openpilot.selfdrive.controls.lib.longcontrol import LongControl from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel + from openpilot.system.hardware import HARDWARE +from openpilot.system.version import get_short_branch SOFT_DISABLE_TIME = 3 # seconds LDW_MIN_SPEED = 31 * CV.MPH_TO_MS LANE_DEPARTURE_THRESHOLD = 0.1 +CAMERA_OFFSET = 0.04 REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ @@ -41,9 +47,9 @@ IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} ThermalStatus = log.DeviceState.ThermalStatus State = log.ControlsState.OpenpilotState PandaType = log.PandaState.PandaType -Desire = log.LateralPlan.Desire -LaneChangeState = log.LateralPlan.LaneChangeState -LaneChangeDirection = log.LateralPlan.LaneChangeDirection +Desire = log.Desire +LaneChangeState = log.LaneChangeState +LaneChangeDirection = log.LaneChangeDirection EventName = car.CarEvent.EventName ButtonType = car.CarState.ButtonEvent.Type SafetyModel = car.CarParams.SafetyModel @@ -55,23 +61,110 @@ ACTIVE_STATES = (State.enabled, State.softDisabling, State.overriding) ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES) +class CarD: + CI: CarInterfaceBase + CS: car.CarState + + def __init__(self, CI=None): + self.can_sock = messaging.sub_sock('can', timeout=20) + self.sm = messaging.SubMaster(['pandaStates']) + self.pm = messaging.PubMaster(['sendcan', 'carState', 'carParams']) + + self.can_rcv_timeout_counter = 0 # conseuctive timeout count + self.can_rcv_cum_timeout_counter = 0 # cumulative timeout count + + self.params = Params() + + if CI is None: + # wait for one pandaState and one CAN packet + print("Waiting for CAN messages...") + get_one_can(self.can_sock) + + num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates) + experimental_long_allowed = self.params.get_bool("ExperimentalLongitudinalEnabled") + self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], experimental_long_allowed, num_pandas) + else: + self.CI, self.CP = CI, CI.CP + + def initialize(self): + """Initialize CarInterface, once controls are ready""" + self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) + + def state_update(self, CC: car.CarControl): + """carState update loop, driven by can""" + + # TODO: This should not depend on carControl + + # Update carState from CAN + can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) + self.CS = self.CI.update(CC, can_strs) + + self.sm.update(0) + + can_rcv_valid = len(can_strs) > 0 + + # Check for CAN timeout + if not can_rcv_valid: + self.can_rcv_timeout_counter += 1 + self.can_rcv_cum_timeout_counter += 1 + else: + self.can_rcv_timeout_counter = 0 + + self.can_rcv_timeout = self.can_rcv_timeout_counter >= 5 + + if can_rcv_valid and REPLAY: + self.can_log_mono_time = messaging.log_from_bytes(can_strs[0]).logMonoTime + + return self.CS + + def state_publish(self, car_events): + """carState and carParams publish loop""" + + # TODO: carState should be independent of the event loop + + # carState + cs_send = messaging.new_message('carState') + cs_send.valid = self.CS.canValid + cs_send.carState = self.CS + cs_send.carState.events = car_events + self.pm.send('carState', cs_send) + + # carParams - logged every 50 seconds (> 1 per segment) + if (self.sm.frame % int(50. / DT_CTRL) == 0): + cp_send = messaging.new_message('carParams') + cp_send.valid = True + cp_send.carParams = self.CP + self.pm.send('carParams', cp_send) + + def controls_update(self, CC: car.CarControl): + """control update loop, driven by carControl""" + + # send car controls over can + now_nanos = self.can_log_mono_time if REPLAY else int(time.monotonic() * 1e9) + actuators_output, can_sends = self.CI.apply(CC, now_nanos) + self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=self.CS.canValid)) + + return actuators_output + + class Controls: def __init__(self, CI=None): + self.card = CarD(CI) + + self.CP = self.card.CP + self.CI = self.card.CI + config_realtime_process(4, Priority.CTRL_HIGH) # Ensure the current branch is cached, otherwise the first iteration of controlsd lags - self.branch = get_short_branch("") + self.branch = get_short_branch() # Setup sockets - self.pm = messaging.PubMaster(['sendcan', 'controlsState', 'carState', - 'carControl', 'carEvents', 'carParams']) + self.pm = messaging.PubMaster(['controlsState', 'carControl', 'onroadEvents']) self.sensor_packets = ["accelerometer", "gyroscope"] self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] - can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 20 - self.can_sock = messaging.sub_sock('can', timeout=can_timeout) - self.log_sock = messaging.sub_sock('androidLog') self.params = Params() @@ -79,23 +172,13 @@ class Controls: if SIMULATION: ignore += ['driverCameraState', 'managerState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', - 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', + 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'testJoystick'] + self.camera_packets + self.sensor_packets, - ignore_alive=ignore, ignore_avg_freq=['radarState', 'testJoystick']) + ignore_alive=ignore, ignore_avg_freq=ignore+['radarState', 'testJoystick'], ignore_valid=['testJoystick', ], + frequency=int(1/DT_CTRL)) - if CI is None: - # wait for one pandaState and one CAN packet - print("Waiting for CAN messages...") - get_one_can(self.can_sock) - - num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates) - experimental_long_allowed = self.params.get_bool("ExperimentalLongitudinalEnabled") and not is_release_branch() - self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], experimental_long_allowed, num_pandas) - else: - self.CI, self.CP = CI, CI.CP - - self.joystick_mode = self.params.get_bool("JoystickDebugMode") or self.CP.notCar + self.joystick_mode = self.params.get_bool("JoystickDebugMode") # set alternative experiences from parameters self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") @@ -107,16 +190,15 @@ class Controls: self.is_metric = self.params.get_bool("IsMetric") self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle") - passive = self.params.get_bool("Passive") or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = HARDWARE.get_sound_card_online() car_recognized = self.CP.carName != 'mock' - controller_available = self.CI.CC is not None and not passive and not self.CP.dashcamOnly - self.read_only = not car_recognized or not controller_available or self.CP.dashcamOnly - if self.read_only: + controller_available = self.CI.CC is not None and openpilot_enabled_toggle and not self.CP.dashcamOnly + self.CP.passive = not car_recognized or not controller_available or self.CP.dashcamOnly + if self.CP.passive: safety_config = car.CarParams.SafetyConfig.new_message() safety_config.safetyModel = car.CarParams.SafetyModel.noOutput self.CP.safetyConfigs = [safety_config] @@ -129,11 +211,11 @@ class Controls: # Write CarParams for radard cp_bytes = self.CP.to_bytes() self.params.put("CarParams", cp_bytes) - put_nonblocking("CarParamsCache", cp_bytes) - put_nonblocking("CarParamsPersistent", cp_bytes) + self.params.put_nonblocking("CarParamsCache", cp_bytes) + self.params.put_nonblocking("CarParamsPersistent", cp_bytes) # cleanup old params - if not self.CP.experimentalLongitudinalAvailable or is_release_branch(): + if not self.CP.experimentalLongitudinalAvailable: self.params.remove("ExperimentalLongitudinalEnabled") if not self.CP.openpilotLongitudinalControl: self.params.remove("ExperimentalMode") @@ -161,8 +243,6 @@ class Controls: self.soft_disable_timer = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 - self.can_rcv_timeout_counter = 0 # conseuctive timeout count - self.can_rcv_cum_timeout_counter = 0 # cumulative timeout count self.last_blinker_frame = 0 self.last_steering_pressed_frame = 0 self.distance_traveled = 0 @@ -174,13 +254,10 @@ class Controls: self.last_actuators = car.CarControl.Actuators.new_message() self.steer_limited = False self.desired_curvature = 0.0 - self.desired_curvature_rate = 0.0 self.experimental_mode = False self.v_cruise_helper = VCruiseHelper(self.CP) self.recalibrating_seen = False - # TODO: no longer necessary, aside from process replay - self.sm['liveParameters'].valid = True self.can_log_mono_time = 0 self.startup_event = get_startup_event(car_recognized, controller_available, len(self.CP.carFw) > 0) @@ -193,15 +270,11 @@ class Controls: set_offroad_alert("Offroad_CarUnrecognized", True) else: set_offroad_alert("Offroad_NoFirmware", True) - elif self.read_only: + elif self.CP.passive: self.events.add(EventName.dashcamMode, static=True) - elif self.joystick_mode: - self.events.add(EventName.joystickDebug, static=True) - self.startup_event = None # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) - self.prof = Profiler(False) # off by default def set_initial_state(self): if REPLAY: @@ -214,10 +287,15 @@ class Controls: self.state = State.enabled def update_events(self, CS): - """Compute carEvents from carState""" + """Compute onroadEvents from carState""" self.events.clear() + # Add joystick event, static on cars, dynamic on nonCars + if self.joystick_mode: + self.events.add(EventName.joystickDebug) + self.startup_event = None + # Add startup event if self.startup_event is not None: self.events.add(self.startup_event) @@ -229,7 +307,7 @@ class Controls: return # no more events while in dashcam mode - if self.read_only: + if self.CP.passive: return # Block resume if cruise never previously enabled @@ -293,8 +371,8 @@ class Controls: self.events.add(EventName.calibrationInvalid) # Handle lane change - if self.sm['lateralPlan'].laneChangeState == LaneChangeState.preLaneChange: - direction = self.sm['lateralPlan'].laneChangeDirection + if self.sm['modelV2'].meta.laneChangeState == LaneChangeState.preLaneChange: + direction = self.sm['modelV2'].meta.laneChangeDirection if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ (CS.rightBlindspot and direction == LaneChangeDirection.right): self.events.add(EventName.laneChangeBlocked) @@ -303,7 +381,7 @@ class Controls: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) - elif self.sm['lateralPlan'].laneChangeState in (LaneChangeState.laneChangeStarting, + elif self.sm['modelV2'].meta.laneChangeState in (LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing): self.events.add(EventName.laneChange) @@ -316,7 +394,8 @@ class Controls: else: safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES - if safety_mismatch or pandaState.safetyRxChecksInvalid or self.mismatch_counter >= 200: + # safety mismatch allows some time for boardd to set the safety mode and publish it back from panda + if (safety_mismatch and self.sm.frame*DT_CTRL > 10.) or pandaState.safetyRxChecksInvalid or self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if log.PandaState.FaultType.relayMalfunction in pandaState.faults: @@ -328,7 +407,7 @@ class Controls: num_events = len(self.events) not_running = {p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning} - if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES): + if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES): self.events.add(EventName.processNotRunning) if not_running != self.not_running_prev: cloudlog.event("process_not_running", not_running=not_running, error=True) @@ -351,10 +430,9 @@ class Controls: self.events.add(EventName.canError) # generic catch-all. ideally, a more specific event should be added above instead - can_rcv_timeout = self.can_rcv_timeout_counter >= 5 has_disable_events = self.events.contains(ET.NO_ENTRY) and (self.events.contains(ET.SOFT_DISABLE) or self.events.contains(ET.IMMEDIATE_DISABLE)) no_system_errors = (not has_disable_events) or (len(self.events) == num_events) - if (not self.sm.all_checks() or can_rcv_timeout) and no_system_errors: + if (not self.sm.all_checks() or self.card.can_rcv_timeout) and no_system_errors: if not self.sm.all_alive(): self.events.add(EventName.commIssue) elif not self.sm.all_freq_ok(): @@ -366,7 +444,7 @@ class Controls: 'invalid': [s for s, valid in self.sm.valid.items() if not valid], 'not_alive': [s for s, alive in self.sm.alive.items() if not alive], 'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], - 'can_rcv_timeout': can_rcv_timeout, + 'can_rcv_timeout': self.card.can_rcv_timeout, } if logs != self.logged_comm_issue: cloudlog.event("commIssue", error=True, **logs) @@ -374,19 +452,18 @@ class Controls: else: self.logged_comm_issue = None - if not self.sm['lateralPlan'].mpcSolutionValid: - self.events.add(EventName.plannerError) - if not self.sm['liveLocationKalman'].posenetOK: - self.events.add(EventName.posenetInvalid) - if not self.sm['liveLocationKalman'].deviceStable: - self.events.add(EventName.deviceFalling) - if not self.sm['liveLocationKalman'].inputsOK: - self.events.add(EventName.locationdTemporaryError) - if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): - self.events.add(EventName.paramsdTemporaryError) + if not (self.CP.notCar and self.joystick_mode): + if not self.sm['liveLocationKalman'].posenetOK: + self.events.add(EventName.posenetInvalid) + if not self.sm['liveLocationKalman'].deviceStable: + self.events.add(EventName.deviceFalling) + if not self.sm['liveLocationKalman'].inputsOK: + self.events.add(EventName.locationdTemporaryError) + if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): + self.events.add(EventName.paramsdTemporaryError) # conservative HW alert. if the data or frequency are off, locationd will throw an error - if any((self.sm.frame - self.sm.rcv_frame[s])*DT_CTRL > 10. for s in self.sensor_packets): + if any((self.sm.frame - self.sm.recv_frame[s])*DT_CTRL > 10. for s in self.sensor_packets): self.events.add(EventName.sensorDataInvalid) if not REPLAY: @@ -416,9 +493,12 @@ class Controls: # TODO: fix simulator if not SIMULATION or REPLAY: + # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes if not self.sm['liveLocationKalman'].gpsOK and self.sm['liveLocationKalman'].inputsOK and (self.distance_traveled > 1000): - # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes self.events.add(EventName.noGps) + if self.sm['liveLocationKalman'].gpsOK: + self.distance_traveled = 0 + self.distance_traveled += CS.vEgo * DT_CTRL if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) @@ -426,17 +506,13 @@ class Controls: def data_sample(self): """Receive data from sockets and update carState""" - # Update carState from CAN - can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) - CS = self.CI.update(self.CC, can_strs) - if len(can_strs) and REPLAY: - self.can_log_mono_time = messaging.log_from_bytes(can_strs[0]).logMonoTime + CS = self.card.state_update(self.CC) self.sm.update(0) if not self.initialized: all_valid = CS.canValid and self.sm.all_checks() - timed_out = self.sm.frame * DT_CTRL > (6. if REPLAY else 3.5) + timed_out = self.sm.frame * DT_CTRL > 6. if all_valid or timed_out or (SIMULATION and not REPLAY): available_streams = VisionIpcClient.available_streams("camerad", block=False) if VisionStreamType.VISION_STREAM_ROAD not in available_streams: @@ -444,19 +520,23 @@ class Controls: if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: self.sm.ignore_alive.append('wideRoadCameraState') - if not self.read_only: - self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) + if not self.CP.passive: + self.card.initialize() self.initialized = True self.set_initial_state() - put_bool_nonblocking("ControlsReady", True) - - # Check for CAN timeout - if not can_strs: - self.can_rcv_timeout_counter += 1 - self.can_rcv_cum_timeout_counter += 1 - else: - self.can_rcv_timeout_counter = 0 + self.params.put_bool_nonblocking("ControlsReady", True) + + cloudlog.event( + "controlsd.initialized", + dt=self.sm.frame*DT_CTRL, + timeout=timed_out, + canValid=CS.canValid, + invalid=[s for s, valid in self.sm.valid.items() if not valid], + not_alive=[s for s, alive in self.sm.alive.items() if not alive], + not_freq_ok=[s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], + error=True, + ) # When the panda and controlsd do not agree on controls_allowed # we want to disengage openpilot. However the status from the panda goes through @@ -470,8 +550,6 @@ class Controls: if ps.safetyModel not in IGNORED_SAFETY_MODES): self.mismatch_counter += 1 - self.distance_traveled += CS.vEgo * DT_CTRL - return CS def state_transition(self, CS): @@ -576,8 +654,8 @@ class Controls: self.LaC.update_live_torque_params(torque_params.latAccelFactorFiltered, torque_params.latAccelOffsetFiltered, torque_params.frictionCoefficientFiltered) - lat_plan = self.sm['lateralPlan'] long_plan = self.sm['longitudinalPlan'] + model_v2 = self.sm['modelV2'] CC = car.CarControl.new_message() CC.enabled = self.enabled @@ -592,9 +670,9 @@ class Controls: actuators.longControlState = self.LoC.long_control_state # Enable blinkers while lane changing - if self.sm['lateralPlan'].laneChangeState != LaneChangeState.off: - CC.leftBlinker = self.sm['lateralPlan'].laneChangeDirection == LaneChangeDirection.left - CC.rightBlinker = self.sm['lateralPlan'].laneChangeDirection == LaneChangeDirection.right + if model_v2.meta.laneChangeState != LaneChangeState.off: + CC.leftBlinker = model_v2.meta.laneChangeDirection == LaneChangeDirection.left + CC.rightBlinker = model_v2.meta.laneChangeDirection == LaneChangeDirection.right if CS.leftBlinker or CS.rightBlinker: self.last_blinker_frame = self.sm.frame @@ -609,23 +687,20 @@ class Controls: if not self.joystick_mode: # accel PID loop pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_helper.v_cruise_kph * CV.KPH_TO_MS) - t_since_plan = (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) * DT_CTRL + t_since_plan = (self.sm.frame - self.sm.recv_frame['longitudinalPlan']) * DT_CTRL actuators.accel = self.LoC.update(CC.longActive, CS, long_plan, pid_accel_limits, t_since_plan) # Steering PID loop and lateral MPC - self.desired_curvature, self.desired_curvature_rate = get_lag_adjusted_curvature(self.CP, CS.vEgo, - lat_plan.psis, - lat_plan.curvatures, - lat_plan.curvatureRates) - actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, - self.last_actuators, self.steer_limited, self.desired_curvature, - self.desired_curvature_rate, self.sm['liveLocationKalman']) + self.desired_curvature = clip_curvature(CS.vEgo, self.desired_curvature, model_v2.action.desiredCurvature) actuators.curvature = self.desired_curvature + actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, + self.steer_limited, self.desired_curvature, + self.sm['liveLocationKalman']) else: lac_log = log.ControlsState.LateralDebugState.new_message() - if self.sm.rcv_frame['testJoystick'] > 0: + if self.sm.recv_frame['testJoystick'] > 0: # reset joystick if it hasn't been received in a while - should_reset_joystick = (self.sm.frame - self.sm.rcv_frame['testJoystick'])*DT_CTRL > 0.2 + should_reset_joystick = (self.sm.frame - self.sm.recv_frame['testJoystick'])*DT_CTRL > 0.2 if not should_reset_joystick: joystick_axes = self.sm['testJoystick'].axes else: @@ -637,7 +712,7 @@ class Controls: if CC.latActive: steer = clip(joystick_axes[1], -1, 1) # max angle is 45 for angle-based cars, max curvature is 0.02 - actuators.steer, actuators.steeringAngleDeg, actuators.curvature = steer, steer * 45., steer * -0.02 + actuators.steer, actuators.steeringAngleDeg, actuators.curvature = steer, steer * 90., steer * -0.02 lac_log.active = self.active lac_log.steeringAngleDeg = CS.steeringAngleDeg @@ -658,7 +733,8 @@ class Controls: if undershooting and turning and good_speed and max_torque: lac_log.active and self.events.add(EventName.steerSaturated) elif lac_log.saturated: - dpath_points = lat_plan.dPathPoints + # TODO probably should not use dpath_points but curvature + dpath_points = model_v2.position.y if len(dpath_points): # Check if we deviated from the path # TODO use desired vs actual curvature @@ -699,7 +775,7 @@ class Controls: CC.cruiseControl.override = self.enabled and not CC.longActive and self.CP.openpilotLongitudinalControl CC.cruiseControl.cancel = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) - if self.joystick_mode and self.sm.rcv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: + if self.joystick_mode and self.sm.recv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: CC.cruiseControl.cancel = True speeds = self.sm['longitudinalPlan'].speeds @@ -749,11 +825,8 @@ class Controls: if current_alert: hudControl.visualAlert = current_alert.visual_alert - if not self.read_only and self.initialized: - # send car controls over can - now_nanos = self.can_log_mono_time if REPLAY else int(time.monotonic() * 1e9) - self.last_actuators, can_sends = self.CI.apply(CC, now_nanos) - self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) + if not self.CP.passive and self.initialized: + self.last_actuators = self.card.controls_update(CC) CC.actuatorsOutput = self.last_actuators if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.steer_limited = abs(CC.actuators.steeringAngleDeg - CC.actuatorsOutput.steeringAngleDeg) > \ @@ -784,12 +857,11 @@ class Controls: controlsState.alertSound = current_alert.audible_alert controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] - controlsState.lateralPlanMonoTime = self.sm.logMonoTime['lateralPlan'] + controlsState.lateralPlanMonoTime = self.sm.logMonoTime['modelV2'] controlsState.enabled = self.enabled controlsState.active = self.active controlsState.curvature = curvature controlsState.desiredCurvature = self.desired_curvature - controlsState.desiredCurvatureRate = self.desired_curvature_rate controlsState.state = self.state controlsState.engageable = not self.events.contains(ET.NO_ENTRY) controlsState.longControlState = self.LoC.long_control_state @@ -802,7 +874,7 @@ class Controls: controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) - controlsState.canErrorCounter = self.can_rcv_cum_timeout_counter + controlsState.canErrorCounter = self.card.can_rcv_cum_timeout_counter controlsState.experimentalMode = self.experimental_mode lat_tuning = self.CP.lateralTuning.which() @@ -817,27 +889,18 @@ class Controls: self.pm.send('controlsState', dat) - # carState car_events = self.events.to_msg() - cs_send = messaging.new_message('carState') - cs_send.valid = CS.canValid - cs_send.carState = CS - cs_send.carState.events = car_events - self.pm.send('carState', cs_send) - # carEvents - logged every second or on change + self.card.state_publish(car_events) + + # onroadEvents - logged every second or on change if (self.sm.frame % int(1. / DT_CTRL) == 0) or (self.events.names != self.events_prev): - ce_send = messaging.new_message('carEvents', len(self.events)) - ce_send.carEvents = car_events - self.pm.send('carEvents', ce_send) + ce_send = messaging.new_message('onroadEvents', len(self.events)) + ce_send.valid = True + ce_send.onroadEvents = car_events + self.pm.send('onroadEvents', ce_send) self.events_prev = self.events.names.copy() - # carParams - logged every 50 seconds (> 1 per segment) - if (self.sm.frame % int(50. / DT_CTRL) == 0): - cp_send = messaging.new_message('carParams') - cp_send.carParams = self.CP - self.pm.send('carParams', cp_send) - # carControl cc_send = messaging.new_message('carControl') cc_send.valid = CS.canValid @@ -849,40 +912,45 @@ class Controls: def step(self): start_time = time.monotonic() - self.prof.checkpoint("Ratekeeper", ignore=True) - - self.is_metric = self.params.get_bool("IsMetric") - self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl # Sample data from sockets and get a carState CS = self.data_sample() cloudlog.timestamp("Data sampled") - self.prof.checkpoint("Sample") self.update_events(CS) cloudlog.timestamp("Events updated") - if not self.read_only and self.initialized: + if not self.CP.passive and self.initialized: # Update control state self.state_transition(CS) - self.prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) CC, lac_log = self.state_control(CS) - self.prof.checkpoint("State Control") - # Publish data self.publish_logs(CS, start_time, CC, lac_log) - self.prof.checkpoint("Sent") self.CS_prev = CS + def params_thread(self, evt): + while not evt.is_set(): + self.is_metric = self.params.get_bool("IsMetric") + self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl + if self.CP.notCar: + self.joystick_mode = self.params.get_bool("JoystickDebugMode") + time.sleep(0.1) + def controlsd_thread(self): - while True: - self.step() - self.rk.monitor_time() - self.prof.display() + e = threading.Event() + t = threading.Thread(target=self.params_thread, args=(e, )) + try: + t.start() + while True: + self.step() + self.rk.monitor_time() + except SystemExit: + e.set() + t.join() def main(): diff --git a/selfdrive/controls/lib/desire_helper.py b/selfdrive/controls/lib/desire_helper.py index d538035070..90b6858649 100644 --- a/selfdrive/controls/lib/desire_helper.py +++ b/selfdrive/controls/lib/desire_helper.py @@ -2,30 +2,30 @@ from cereal import log from openpilot.common.conversions import Conversions as CV from openpilot.common.realtime import DT_MDL -LaneChangeState = log.LateralPlan.LaneChangeState -LaneChangeDirection = log.LateralPlan.LaneChangeDirection +LaneChangeState = log.LaneChangeState +LaneChangeDirection = log.LaneChangeDirection LANE_CHANGE_SPEED_MIN = 20 * CV.MPH_TO_MS LANE_CHANGE_TIME_MAX = 10. DESIRES = { LaneChangeDirection.none: { - LaneChangeState.off: log.LateralPlan.Desire.none, - LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.none, + LaneChangeState.off: log.Desire.none, + LaneChangeState.preLaneChange: log.Desire.none, + LaneChangeState.laneChangeStarting: log.Desire.none, + LaneChangeState.laneChangeFinishing: log.Desire.none, }, LaneChangeDirection.left: { - LaneChangeState.off: log.LateralPlan.Desire.none, - LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.laneChangeLeft, - LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.laneChangeLeft, + LaneChangeState.off: log.Desire.none, + LaneChangeState.preLaneChange: log.Desire.none, + LaneChangeState.laneChangeStarting: log.Desire.laneChangeLeft, + LaneChangeState.laneChangeFinishing: log.Desire.laneChangeLeft, }, LaneChangeDirection.right: { - LaneChangeState.off: log.LateralPlan.Desire.none, - LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.laneChangeRight, - LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.laneChangeRight, + LaneChangeState.off: log.Desire.none, + LaneChangeState.preLaneChange: log.Desire.none, + LaneChangeState.laneChangeStarting: log.Desire.laneChangeRight, + LaneChangeState.laneChangeFinishing: log.Desire.laneChangeRight, }, } @@ -38,7 +38,7 @@ class DesireHelper: self.lane_change_ll_prob = 1.0 self.keep_pulse_timer = 0.0 self.prev_one_blinker = False - self.desire = log.LateralPlan.Desire.none + self.desire = log.Desire.none def update(self, carstate, lateral_active, lane_change_prob): v_ego = carstate.vEgo @@ -110,5 +110,5 @@ class DesireHelper: self.keep_pulse_timer += DT_MDL if self.keep_pulse_timer > 1.0: self.keep_pulse_timer = 0.0 - elif self.desire in (log.LateralPlan.Desire.keepLeft, log.LateralPlan.Desire.keepRight): - self.desire = log.LateralPlan.Desire.none + elif self.desire in (log.Desire.keepLeft, log.Desire.keepRight): + self.desire = log.Desire.none diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index b728f1114c..6a5b22f686 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -3,8 +3,7 @@ import math from cereal import car, log from openpilot.common.conversions import Conversions as CV from openpilot.common.numpy_fast import clip, interp -from openpilot.common.realtime import DT_MDL -from openpilot.selfdrive.modeld.constants import ModelConstants +from openpilot.common.realtime import DT_CTRL # WARNING: this value was determined based on the model's training distribution, # model predictions above this speed can be unpredictable @@ -22,7 +21,6 @@ CAR_ROTATION_RADIUS = 0.0 # EU guidelines MAX_LATERAL_JERK = 5.0 - MAX_VEL_ERR = 5.0 ButtonEvent = car.CarState.ButtonEvent @@ -163,35 +161,14 @@ def rate_limit(new_value, last_value, dw_step, up_step): return clip(new_value, last_value + dw_step, last_value + up_step) -def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): - if len(psis) != CONTROL_N: - psis = [0.0]*CONTROL_N - curvatures = [0.0]*CONTROL_N - curvature_rates = [0.0]*CONTROL_N +def clip_curvature(v_ego, prev_curvature, new_curvature): v_ego = max(MIN_SPEED, v_ego) - - # TODO this needs more thought, use .2s extra for now to estimate other delays - delay = CP.steerActuatorDelay + .2 - - # 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 - current_curvature_desired = curvatures[0] - psi = interp(delay, ModelConstants.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) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755 - safe_desired_curvature_rate = clip(desired_curvature_rate, - -max_curvature_rate, - max_curvature_rate) - safe_desired_curvature = clip(desired_curvature, - current_curvature_desired - max_curvature_rate * DT_MDL, - current_curvature_desired + max_curvature_rate * DT_MDL) - - return safe_desired_curvature, safe_desired_curvature_rate + safe_desired_curvature = clip(new_curvature, + prev_curvature - max_curvature_rate * DT_CTRL, + prev_curvature + max_curvature_rate * DT_CTRL) + + return safe_desired_curvature def get_friction(lateral_accel_error: float, lateral_accel_deadzone: float, friction_threshold: float, diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 79bead3ac8..d68c95bcf5 100755 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -224,7 +224,7 @@ def user_soft_disable_alert(alert_text_2: str) -> AlertCallbackType: return func def startup_master_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - branch = get_short_branch("") # Ensure get_short_branch is cached to avoid lags on startup + branch = get_short_branch() # Ensure get_short_branch is cached to avoid lags on startup if "REPLAY" in os.environ: branch = "replay" @@ -767,12 +767,12 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { # is thrown. This can mean a service crashed, did not broadcast a message for # ten times the regular interval, or the average interval is more than 10% too high. EventName.commIssue: { - ET.SOFT_DISABLE: soft_disable_alert("Communication Issue between Processes"), + ET.SOFT_DISABLE: soft_disable_alert("Communication Issue Between Processes"), ET.NO_ENTRY: comm_issue_alert, }, EventName.commIssueAvgFreq: { - ET.SOFT_DISABLE: soft_disable_alert("Low Communication Rate between Processes"), - ET.NO_ENTRY: NoEntryAlert("Low Communication Rate between Processes"), + ET.SOFT_DISABLE: soft_disable_alert("Low Communication Rate Between Processes"), + ET.NO_ENTRY: NoEntryAlert("Low Communication Rate Between Processes"), }, EventName.controlsdLagging: { @@ -912,14 +912,6 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Cruise Is Off"), }, - # For planning the trajectory Model Predictive Control (MPC) is used. This is - # an optimization algorithm that is not guaranteed to find a feasible solution. - # If no solution is found or the solution has a very high cost this alert is thrown. - EventName.plannerError: { - ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Planner Solution Error"), - ET.NO_ENTRY: NoEntryAlert("Planner Solution Error"), - }, - # When the relay in the harness box opens the CAN bus between the LKAS camera # and the rest of the car is separated. When messages from the LKAS camera # are received on the car side this usually means the relay hasn't opened correctly diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index 30e1918442..fddb331ccb 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -17,7 +17,7 @@ class LatControl(ABC): self.steer_max = 1.0 @abstractmethod - def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): pass def reset(self): diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index b13d41e51c..329c486eb9 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -11,7 +11,7 @@ class LatControlAngle(LatControl): super().__init__(CP, CI) self.sat_check_min_speed = 5. - def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): angle_log = log.ControlsState.LateralAngleState.new_message() if not active: diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index c41130af95..9e6160838b 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -17,7 +17,7 @@ class LatControlPID(LatControl): super().reset() self.pid.reset() - def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): pid_log = log.ControlsState.LateralPIDState.new_message() pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 2c77630632..34b0d47124 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -2,6 +2,7 @@ import math from cereal import log from openpilot.common.numpy_fast import interp +from openpilot.selfdrive.car.interfaces import LatControlInputs from openpilot.selfdrive.controls.lib.latcontrol import LatControl from openpilot.selfdrive.controls.lib.pid import PIDController from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY @@ -36,18 +37,18 @@ class LatControlTorque(LatControl): self.torque_params.latAccelOffset = latAccelOffset self.torque_params.friction = friction - def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): pid_log = log.ControlsState.LateralTorqueState.new_message() - if not active: output_torque = 0.0 pid_log.active = False else: + actual_curvature_vm = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) + roll_compensation = params.roll * ACCELERATION_DUE_TO_GRAVITY if self.use_steering_angle: - actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) + actual_curvature = actual_curvature_vm curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) else: - actual_curvature_vm = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) actual_curvature_llk = llk.angularVelocityCalibrated.value[2] / CS.vEgo actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_llk]) curvature_deadzone = 0.0 @@ -61,15 +62,15 @@ class LatControlTorque(LatControl): low_speed_factor = interp(CS.vEgo, LOW_SPEED_X, LOW_SPEED_Y)**2 setpoint = desired_lateral_accel + low_speed_factor * desired_curvature measurement = actual_lateral_accel + low_speed_factor * actual_curvature - gravity_adjusted_lateral_accel = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY - torque_from_setpoint = self.torque_from_lateral_accel(setpoint, self.torque_params, setpoint, - lateral_accel_deadzone, friction_compensation=False) - torque_from_measurement = self.torque_from_lateral_accel(measurement, self.torque_params, measurement, - lateral_accel_deadzone, friction_compensation=False) + gravity_adjusted_lateral_accel = desired_lateral_accel - roll_compensation + torque_from_setpoint = self.torque_from_lateral_accel(LatControlInputs(setpoint, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, + setpoint, lateral_accel_deadzone, friction_compensation=False, gravity_adjusted=False) + torque_from_measurement = self.torque_from_lateral_accel(LatControlInputs(measurement, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, + measurement, lateral_accel_deadzone, friction_compensation=False, gravity_adjusted=False) pid_log.error = torque_from_setpoint - torque_from_measurement - ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params, - desired_lateral_accel - actual_lateral_accel, - lateral_accel_deadzone, friction_compensation=True) + ff = self.torque_from_lateral_accel(LatControlInputs(gravity_adjusted_lateral_accel, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, + desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, friction_compensation=True, + gravity_adjusted=True) freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5 output_torque = self.pid.update(pid_log.error, diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py deleted file mode 100644 index 2417eb3c68..0000000000 --- a/selfdrive/controls/lib/lateral_planner.py +++ /dev/null @@ -1,74 +0,0 @@ -import numpy as np -from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, MIN_SPEED, get_speed_error -from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper -import cereal.messaging as messaging -from cereal import log - -TRAJECTORY_SIZE = 33 -CAMERA_OFFSET = 0.04 - -class LateralPlanner: - def __init__(self, CP, debug=False): - self.DH = DesireHelper() - - # Vehicle model parameters used to calculate lateral movement of car - self.factor1 = CP.wheelbase - CP.centerToFront - self.factor2 = (CP.centerToFront * CP.mass) / (CP.wheelbase * CP.tireStiffnessRear) - self.last_cloudlog_t = 0 - self.solution_invalid_cnt = 0 - - self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) - self.velocity_xyz = np.zeros((TRAJECTORY_SIZE, 3)) - self.v_plan = np.zeros((TRAJECTORY_SIZE,)) - self.x_sol = np.zeros((TRAJECTORY_SIZE, 4), dtype=np.float32) - self.v_ego = MIN_SPEED - self.l_lane_change_prob = 0.0 - self.r_lane_change_prob = 0.0 - - self.debug_mode = debug - - def update(self, sm): - v_ego_car = sm['carState'].vEgo - - # Parse model predictions - md = sm['modelV2'] - if len(md.position.x) == TRAJECTORY_SIZE and len(md.velocity.x) == TRAJECTORY_SIZE and len(md.lateralPlannerSolution.x) == TRAJECTORY_SIZE: - self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z]) - self.velocity_xyz = np.column_stack([md.velocity.x, md.velocity.y, md.velocity.z]) - car_speed = np.linalg.norm(self.velocity_xyz, axis=1) - get_speed_error(md, v_ego_car) - self.v_plan = np.clip(car_speed, MIN_SPEED, np.inf) - self.v_ego = self.v_plan[0] - self.x_sol = np.column_stack([md.lateralPlannerSolution.x, md.lateralPlannerSolution.y, md.lateralPlannerSolution.yaw, md.lateralPlannerSolution.yawRate]) - - # Lane change logic - desire_state = md.meta.desireState - if len(desire_state): - self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] - self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] - lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob - self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob) - - def publish(self, sm, pm): - plan_send = messaging.new_message('lateralPlan') - plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState', 'modelV2']) - - lateralPlan = plan_send.lateralPlan - lateralPlan.modelMonoTime = sm.logMonoTime['modelV2'] - lateralPlan.dPathPoints = self.path_xyz[:,1].tolist() - lateralPlan.psis = self.x_sol[0:CONTROL_N, 2].tolist() - - lateralPlan.curvatures = (self.x_sol[0:CONTROL_N, 3]/self.v_ego).tolist() - lateralPlan.curvatureRates = [float(0) for _ in range(CONTROL_N-1)] # TODO: unused - - lateralPlan.mpcSolutionValid = bool(1) - lateralPlan.solverExecutionTime = 0.0 - if self.debug_mode: - lateralPlan.solverState = log.LateralPlan.SolverState.new_message() - lateralPlan.solverState.x = self.x_sol.tolist() - - lateralPlan.desire = self.DH.desire - lateralPlan.useLaneLines = False - lateralPlan.laneChangeState = self.DH.lane_change_state - lateralPlan.laneChangeDirection = self.DH.lane_change_direction - - pm.send('lateralPlan', plan_send) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index a23ba1eaf6..39cfda4e8a 100755 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -4,7 +4,7 @@ import time import numpy as np from cereal import log from openpilot.common.numpy_fast import clip -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog # WARNING: imports outside of constants will not trigger a rebuild from openpilot.selfdrive.modeld.constants import index_function from openpilot.selfdrive.car.interfaces import ACCEL_MIN diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index b1eff5302f..018768f248 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -15,7 +15,7 @@ from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N, get_speed_error -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog LON_MPC_STEP = 0.2 # first step is 0.2s A_CRUISE_MIN = -1.2 @@ -47,13 +47,14 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class LongitudinalPlanner: - def __init__(self, CP, init_v=0.0, init_a=0.0): + def __init__(self, CP, init_v=0.0, init_a=0.0, dt=DT_MDL): self.CP = CP self.mpc = LongitudinalMpc() self.fcw = False + self.dt = dt self.a_desired = init_a - self.v_desired_filter = FirstOrderFilter(init_v, 2.0, DT_MDL) + self.v_desired_filter = FirstOrderFilter(init_v, 2.0, self.dt) self.v_model_error = 0.0 self.v_desired_trajectory = np.zeros(CONTROL_N) @@ -148,8 +149,8 @@ class LongitudinalPlanner: # Interpolate 0.05 seconds and save as starting point for next iteration a_prev = self.a_desired - self.a_desired = float(interp(DT_MDL, ModelConstants.T_IDXS[:CONTROL_N], self.a_desired_trajectory)) - self.v_desired_filter.x = self.v_desired_filter.x + DT_MDL * (self.a_desired + a_prev) / 2.0 + self.a_desired = float(interp(self.dt, ModelConstants.T_IDXS[:CONTROL_N], self.a_desired_trajectory)) + self.v_desired_filter.x = self.v_desired_filter.x + self.dt * (self.a_desired + a_prev) / 2.0 def publish(self, sm, pm): plan_send = messaging.new_message('longitudinalPlan') diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 15dbd4c5e2..eeeeda050e 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -1,29 +1,19 @@ #!/usr/bin/env python3 -import os -import numpy as np from cereal import car from openpilot.common.params import Params from openpilot.common.realtime import Priority, config_realtime_process -from openpilot.system.swaglog import cloudlog -from openpilot.selfdrive.modeld.constants import ModelConstants +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner -from openpilot.selfdrive.controls.lib.lateral_planner import LateralPlanner import cereal.messaging as messaging -def cumtrapz(x, t): - return np.concatenate([[0], np.cumsum(((x[0:-1] + x[1:])/2) * np.diff(t))]) - -def publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner): - plan_odo = cumtrapz(longitudinal_planner.v_desired_trajectory_full, ModelConstants.T_IDXS) - model_odo = cumtrapz(lateral_planner.v_plan, ModelConstants.T_IDXS) - +def publish_ui_plan(sm, pm, longitudinal_planner): ui_send = messaging.new_message('uiPlan') ui_send.valid = sm.all_checks(service_list=['carState', 'controlsState', 'modelV2']) uiPlan = ui_send.uiPlan uiPlan.frameId = sm['modelV2'].frameId - uiPlan.position.x = np.interp(plan_odo, model_odo, lateral_planner.x_sol[:,0]).tolist() - uiPlan.position.y = np.interp(plan_odo, model_odo, lateral_planner.x_sol[:,1]).tolist() - uiPlan.position.z = np.interp(plan_odo, model_odo, lateral_planner.path_xyz[:,2]).tolist() + uiPlan.position.x = list(sm['modelV2'].position.x) + uiPlan.position.y = list(sm['modelV2'].position.y) + uiPlan.position.z = list(sm['modelV2'].position.z) uiPlan.accel = longitudinal_planner.a_desired_trajectory_full.tolist() pm.send('uiPlan', ui_send) @@ -36,24 +26,17 @@ def plannerd_thread(): CP = msg cloudlog.info("plannerd got CarParams: %s", CP.carName) - debug_mode = bool(int(os.getenv("DEBUG", "0"))) - longitudinal_planner = LongitudinalPlanner(CP) - lateral_planner = LateralPlanner(CP, debug=debug_mode) - - pm = messaging.PubMaster(['longitudinalPlan', 'lateralPlan', 'uiPlan']) + pm = messaging.PubMaster(['longitudinalPlan', 'uiPlan']) sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2'], - poll=['radarState', 'modelV2'], ignore_avg_freq=['radarState']) + poll='modelV2', ignore_avg_freq=['radarState']) while True: sm.update() - if sm.updated['modelV2']: - lateral_planner.update(sm) - lateral_planner.publish(sm, pm) longitudinal_planner.update(sm) longitudinal_planner.publish(sm, pm) - publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner) + publish_ui_plan(sm, pm, longitudinal_planner) def main(): plannerd_thread() diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index ec42ae66f2..b0b9350dec 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -8,10 +8,10 @@ import capnp from cereal import messaging, log, car from openpilot.common.numpy_fast import interp from openpilot.common.params import Params -from openpilot.common.realtime import Ratekeeper, Priority, config_realtime_process -from openpilot.system.swaglog import cloudlog +from openpilot.common.realtime import DT_CTRL, Ratekeeper, Priority, config_realtime_process +from openpilot.common.swaglog import cloudlog -from openpilot.common.kalman.simple_kalman import KF1D +from openpilot.common.simple_kalman import KF1D # Default lead acceleration decay set to 50% at 1s @@ -201,6 +201,7 @@ class RadarD: self.v_ego = 0.0 self.v_ego_hist = deque([0.0], maxlen=delay+1) + self.last_v_ego_frame = -1 self.radar_state: Optional[capnp._DynamicStructBuilder] = None self.radar_state_valid = False @@ -208,6 +209,7 @@ class RadarD: self.ready = False def update(self, sm: messaging.SubMaster, rr: Optional[car.RadarData]): + self.ready = sm.seen['modelV2'] self.current_time = 1e-9*max(sm.logMonoTime.values()) radar_points = [] @@ -216,11 +218,10 @@ class RadarD: radar_points = rr.points radar_errors = rr.errors - if sm.updated['carState']: + if sm.recv_frame['carState'] != self.last_v_ego_frame: self.v_ego = sm['carState'].vEgo self.v_ego_hist.append(self.v_ego) - if sm.updated['modelV2']: - self.ready = True + self.last_v_ego_frame = sm.recv_frame['carState'] ar_pts = {} for pt in radar_points: @@ -270,6 +271,7 @@ class RadarD: # publish tracks for UI debugging (keep last) tracks_msg = messaging.new_message('liveTracks', len(self.tracks)) + tracks_msg.valid = self.radar_state_valid for index, tid in enumerate(sorted(self.tracks.keys())): tracks_msg.liveTracks[index] = { "trackId": tid, @@ -281,7 +283,7 @@ class RadarD: # fuses camera and radar data for best lead detection -def radard_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None, can_sock: Optional[messaging.SubSocket] = None): +def main(): config_realtime_process(5, Priority.CTRL_LOW) # wait for stats about the car to come in from controls @@ -295,12 +297,9 @@ def radard_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[messagi RadarInterface = importlib.import_module(f'selfdrive.car.{CP.carName}.radar_interface').RadarInterface # *** setup messaging - if can_sock is None: - can_sock = messaging.sub_sock('can') - if sm is None: - sm = messaging.SubMaster(['modelV2', 'carState'], ignore_avg_freq=['modelV2', 'carState']) # Can't check average frequency, since radar determines timing - if pm is None: - pm = messaging.PubMaster(['radarState', 'liveTracks']) + can_sock = messaging.sub_sock('can') + sm = messaging.SubMaster(['modelV2', 'carState'], frequency=int(1./DT_CTRL)) + pm = messaging.PubMaster(['radarState', 'liveTracks']) RI = RadarInterface(CP) @@ -310,21 +309,15 @@ def radard_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[messagi while 1: can_strings = messaging.drain_sock_raw(can_sock, wait_for_one=True) rr = RI.update(can_strings) - + sm.update(0) if rr is None: continue - sm.update(0) - RD.update(sm, rr) RD.publish(pm, -rk.remaining*1000.0) rk.monitor_time() -def main(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None, can_sock: messaging.SubSocket = None): - radard_thread(sm, pm, can_sock) - - if __name__ == "__main__": main() diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index db18f4c622..787e9bc738 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -1,14 +1,14 @@ #!/usr/bin/env python3 -import os import sys import argparse import json import codecs -import cereal.messaging as messaging from hexdump import hexdump from cereal import log from cereal.services import SERVICE_LIST +from openpilot.tools.lib.live_logreader import raw_live_logreader + codecs.register_error("strict", codecs.backslashreplace_errors) @@ -22,32 +22,20 @@ if __name__ == "__main__": parser.add_argument('--no-print', action='store_true') parser.add_argument('--addr', default='127.0.0.1') parser.add_argument('--values', help='values to monitor (instead of entire event)') - parser.add_argument("socket", type=str, nargs='*', help="socket names to dump. defaults to all services defined in cereal") + parser.add_argument("socket", type=str, nargs='*', default=list(SERVICE_LIST.keys()), help="socket names to dump. defaults to all services defined in cereal") args = parser.parse_args() - if args.addr != "127.0.0.1": - os.environ["ZMQ"] = "1" - messaging.context = messaging.Context() - - poller = messaging.Poller() - - for m in args.socket if len(args.socket) > 0 else SERVICE_LIST: - messaging.sub_sock(m, poller, addr=args.addr) + lr = raw_live_logreader(args.socket, args.addr) values = None if args.values: values = [s.strip().split(".") for s in args.values.split(",")] - while 1: - polld = poller.poll(100) - for sock in polld: - msg = sock.receive() - with log.Event.from_bytes(msg) as log_evt: - evt = log_evt - + for msg in lr: + with log.Event.from_bytes(msg) as evt: if not args.no_print: if args.pipe: - sys.stdout.write(msg) + sys.stdout.write(str(msg)) sys.stdout.flush() elif args.raw: hexdump(msg) diff --git a/selfdrive/debug/filter_log_message.py b/selfdrive/debug/filter_log_message.py index 20cef0fcc0..9cbab0b41f 100755 --- a/selfdrive/debug/filter_log_message.py +++ b/selfdrive/debug/filter_log_message.py @@ -1,11 +1,9 @@ #!/usr/bin/env python3 -import os import argparse import json import cereal.messaging as messaging from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.route import Route LEVELS = { "DEBUG": 10, @@ -48,36 +46,27 @@ def print_androidlog(t, msg): if __name__ == "__main__": parser = argparse.ArgumentParser() + parser.add_argument('--absolute', action='store_true') parser.add_argument('--level', default='DEBUG') parser.add_argument('--addr', default='127.0.0.1') parser.add_argument("route", type=str, nargs='*', help="route name + segment number for offline usage") args = parser.parse_args() - logs = None - if len(args.route): - if os.path.exists(args.route[0]): - logs = [args.route[0]] - else: - r = Route(args.route[0]) - logs = [q_log if r_log is None else r_log for (q_log, r_log) in zip(r.qlog_paths(), r.log_paths(), strict=True)] - - if len(args.route) == 2 and logs: - n = int(args.route[1]) - logs = [logs[n]] - min_level = LEVELS[args.level] - if logs: - for log in logs: - if log: - lr = LogReader(log) - for m in lr: - if m.which() == 'logMessage': - print_logmessage(m.logMonoTime, m.logMessage, min_level) - elif m.which() == 'errorLogMessage' and 'qlog' in log: - print_logmessage(m.logMonoTime, m.errorLogMessage, min_level) - elif m.which() == 'androidLog': - print_androidlog(m.logMonoTime, m.androidLog) + if args.route: + st = None if not args.absolute else 0 + for route in args.route: + lr = LogReader(route, sort_by_time=True) + for m in lr: + if st is None: + st = m.logMonoTime + if m.which() == 'logMessage': + print_logmessage(m.logMonoTime-st, m.logMessage, min_level) + elif m.which() == 'errorLogMessage': + print_logmessage(m.logMonoTime-st, m.errorLogMessage, min_level) + elif m.which() == 'androidLog': + print_androidlog(m.logMonoTime-st, m.androidLog) else: sm = messaging.SubMaster(['logMessage', 'androidLog'], addr=args.addr) while True: diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py new file mode 100755 index 0000000000..bd5822729a --- /dev/null +++ b/selfdrive/debug/format_fingerprints.py @@ -0,0 +1,81 @@ +#!/usr/bin/env python3 +import jinja2 +import os + +from cereal import car +from openpilot.common.basedir import BASEDIR +from openpilot.selfdrive.car.interfaces import get_interface_attr + +Ecu = car.CarParams.Ecu + +CARS = get_interface_attr('CAR') +FW_VERSIONS = get_interface_attr('FW_VERSIONS') +FINGERPRINTS = get_interface_attr('FINGERPRINTS') +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + +FINGERPRINTS_PY_TEMPLATE = jinja2.Template(""" +{%- if FINGERPRINTS[brand] %} +# ruff: noqa: E501 +{% endif %} +{% if FW_VERSIONS[brand] %} +from cereal import car +{% endif %} +from openpilot.selfdrive.car.{{brand}}.values import CAR +{% if FW_VERSIONS[brand] %} + +Ecu = car.CarParams.Ecu +{% endif %} +{% if comments +%} +{{ comments | join() }} +{% endif %} +{% if FINGERPRINTS[brand] %} + +FINGERPRINTS = { +{% for car, fingerprints in FINGERPRINTS[brand].items() %} + CAR.{{car.name}}: [{ +{% for fingerprint in fingerprints %} +{% if not loop.first %} + {{ "{" }} +{% endif %} + {% for key, value in fingerprint.items() %}{{key}}: {{value}}{% if not loop.last %}, {% endif %}{% endfor %} + + }{% if loop.last %}]{% endif %}, +{% endfor %} +{% endfor %} +} +{% endif %} + +FW_VERSIONS{% if not FW_VERSIONS[brand] %}: dict[str, dict[tuple, list[bytes]]]{% endif %} = { +{% for car, _ in FW_VERSIONS[brand].items() %} + CAR.{{car.name}}: { +{% for key, fw_versions in FW_VERSIONS[brand][car].items() %} + (Ecu.{{ECU_NAME[key[0]]}}, 0x{{"%0x" | format(key[1] | int)}}, \ +{% if key[2] %}0x{{"%0x" | format(key[2] | int)}}{% else %}{{key[2]}}{% endif %}): [ + {% for fw_version in (fw_versions + extra_fw_versions.get(car, {}).get(key, [])) | unique | sort %} + {{fw_version}}, + {% endfor %} + ], +{% endfor %} + }, +{% endfor %} +} + +""", trim_blocks=True) + + +def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tuple, list[bytes]]] = None): + extra_fw_versions = extra_fw_versions or {} + + fingerprints_file = os.path.join(BASEDIR, f"selfdrive/car/{brand}/fingerprints.py") + with open(fingerprints_file, "r") as f: + comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] + + with open(fingerprints_file, "w") as f: + f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, ECU_NAME=ECU_NAME, + FINGERPRINTS=FINGERPRINTS, FW_VERSIONS=FW_VERSIONS, + extra_fw_versions=extra_fw_versions)) + + +if __name__ == "__main__": + for brand in FW_VERSIONS.keys(): + format_brand_fw_versions(brand) diff --git a/selfdrive/locationd/SConscript b/selfdrive/locationd/SConscript index a6febe0170..07555a6087 100644 --- a/selfdrive/locationd/SConscript +++ b/selfdrive/locationd/SConscript @@ -1,10 +1,37 @@ -Import('env', 'common', 'cereal', 'messaging', 'libkf', 'transformations') +Import('env', 'arch', 'common', 'cereal', 'messaging', 'rednose', 'transformations') -loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'pthread'] +loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'pthread', 'dl'] + +# build ekf models +rednose_gen_dir = 'models/generated' +rednose_gen_deps = [ + "models/constants.py", +] +live_ekf = env.RednoseCompileFilter( + target='live', + filter_gen_script='models/live_kf.py', + output_dir=rednose_gen_dir, + extra_gen_artifacts=['live_kf_constants.h'], + gen_script_deps=rednose_gen_deps, +) +car_ekf = env.RednoseCompileFilter( + target='car', + filter_gen_script='models/car_kf.py', + output_dir=rednose_gen_dir, + extra_gen_artifacts=[], + gen_script_deps=rednose_gen_deps, +) + +# locationd build +locationd_sources = ["locationd.cc", "models/live_kf.cc"] -ekf_sym_cc = env.SharedObject("#rednose/helpers/ekf_sym.cc") -locationd_sources = ["locationd.cc", "models/live_kf.cc", ekf_sym_cc] lenv = env.Clone() -lenv["_LIBFLAGS"] += f' {libkf[0].get_labspath()}' -locationd = lenv.Program("locationd", locationd_sources, LIBS=loc_libs + transformations) -lenv.Depends(locationd, libkf) \ No newline at end of file +# ekf filter libraries need to be linked, even if no symbols are used +if arch != "Darwin": + lenv["LINKFLAGS"] += ["-Wl,--no-as-needed"] + +lenv["LIBPATH"].append(Dir(rednose_gen_dir).abspath) +lenv["RPATH"].append(Dir(rednose_gen_dir).abspath) +locationd = lenv.Program("locationd", locationd_sources, LIBS=["live", "ekf_sym"] + loc_libs + transformations) +lenv.Depends(locationd, rednose) +lenv.Depends(locationd, live_ekf) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 566373d7b8..da1c4ec37b 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -15,10 +15,10 @@ from typing import List, NoReturn, Optional from cereal import log import cereal.messaging as messaging from openpilot.common.conversions import Conversions as CV -from openpilot.common.params import Params, put_nonblocking +from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.common.transformations.orientation import rot_from_euler, euler_from_rot -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog MIN_SPEED_FILTER = 15 * CV.MPH_TO_MS MAX_VEL_ANGLE_STD = np.radians(0.25) @@ -64,8 +64,8 @@ class Calibrator: self.not_car = False # Read saved calibration - params = Params() - calibration_params = params.get("CalibrationParams") + self.params = Params() + calibration_params = self.params.get("CalibrationParams") rpy_init = RPY_INIT wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT height = HEIGHT_INIT @@ -164,7 +164,7 @@ class Calibrator: write_this_cycle = (self.idx == 0) and (self.block_idx % (INPUTS_WANTED//5) == 5) if self.param_put and write_this_cycle: - put_nonblocking("CalibrationParams", self.get_msg().to_bytes()) + self.params.put_nonblocking("CalibrationParams", self.get_msg(True).to_bytes()) def handle_v_ego(self, v_ego: float) -> None: self.v_ego = v_ego @@ -227,12 +227,13 @@ class Calibrator: return new_rpy - def get_msg(self) -> capnp.lib.capnp._DynamicStructBuilder: + def get_msg(self, valid: bool) -> capnp.lib.capnp._DynamicStructBuilder: smooth_rpy = self.get_smooth_rpy() msg = messaging.new_message('liveCalibration') - liveCalibration = msg.liveCalibration + msg.valid = valid + liveCalibration = msg.liveCalibration liveCalibration.validBlocks = self.valid_blocks liveCalibration.calStatus = self.cal_status liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) @@ -250,19 +251,16 @@ class Calibrator: return msg - def send_data(self, pm: messaging.PubMaster) -> None: - pm.send('liveCalibration', self.get_msg()) + def send_data(self, pm: messaging.PubMaster, valid: bool) -> None: + pm.send('liveCalibration', self.get_msg(valid)) -def calibrationd_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None) -> NoReturn: +def main() -> NoReturn: gc.disable() set_realtime_priority(1) - if sm is None: - sm = messaging.SubMaster(['cameraOdometry', 'carState', 'carParams'], poll=['cameraOdometry']) - - if pm is None: - pm = messaging.PubMaster(['liveCalibration']) + pm = messaging.PubMaster(['liveCalibration']) + sm = messaging.SubMaster(['cameraOdometry', 'carState', 'carParams'], poll='cameraOdometry') calibrator = Calibrator(param_put=True) @@ -286,11 +284,7 @@ def calibrationd_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[m # 4Hz driven by cameraOdometry if sm.frame % 5 == 0: - calibrator.send_data(pm) - - -def main(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None) -> NoReturn: - calibrationd_thread(sm, pm) + calibrator.send_data(pm, sm.all_checks()) if __name__ == "__main__": diff --git a/selfdrive/locationd/helpers.py b/selfdrive/locationd/helpers.py index bde21f7879..c292e9886c 100644 --- a/selfdrive/locationd/helpers.py +++ b/selfdrive/locationd/helpers.py @@ -1,11 +1,7 @@ import numpy as np -import signal -import sys from typing import List, Optional, Tuple, Any from cereal import log -from openpilot.common.params import Params -from openpilot.system.swaglog import cloudlog class NPQueue: @@ -31,17 +27,17 @@ class PointBuckets: self.buckets_min_points = dict(zip(x_bounds, min_points, strict=True)) self.min_points_total = min_points_total - def bucket_lengths(self) -> List[int]: - return [len(v) for v in self.buckets.values()] - def __len__(self) -> int: - return sum(self.bucket_lengths()) + return sum([len(v) for v in self.buckets.values()]) def is_valid(self) -> bool: individual_buckets_valid = all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values(), strict=True)) total_points_valid = self.__len__() >= self.min_points_total return individual_buckets_valid and total_points_valid + def is_calculable(self) -> bool: + return all(len(v) > 0 for v in self.buckets.values()) + def add_point(self, x: float, y: float, bucket_val: float) -> None: raise NotImplementedError @@ -66,12 +62,3 @@ class ParameterEstimator: def get_msg(self, valid: bool, with_points: bool) -> log.Event: raise NotImplementedError - - -def cache_points_onexit(param_name, estimator, sig, frame): - signal.signal(sig, signal.SIG_DFL) - cloudlog.warning(f"Caching {param_name} param") - params = Params() - msg = estimator.get_msg(valid=True, with_points=True) - params.put(param_name, msg.to_bytes()) - sys.exit(0) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 80882fc951..1050d68b9b 100644 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -678,9 +678,10 @@ void Localizer::configure_gnss_source(const LocalizerGnssSource &source) { } int Localizer::locationd_thread() { + Params params; LocalizerGnssSource source; const char* gps_location_socket; - if (Params().getBool("UbloxAvailable")) { + if (params.getBool("UbloxAvailable")) { source = LocalizerGnssSource::UBLOX; gps_location_socket = "gpsLocationExternal"; } else { @@ -690,10 +691,9 @@ int Localizer::locationd_thread() { this->configure_gnss_source(source); const std::initializer_list service_list = {gps_location_socket, "cameraOdometry", "liveCalibration", - "carState", "carParams", "accelerometer", "gyroscope"}; + "carState", "accelerometer", "gyroscope"}; - // TODO: remove carParams once we're always sending at 100Hz - SubMaster sm(service_list, {}, nullptr, {gps_location_socket, "carParams"}); + SubMaster sm(service_list, {}, nullptr, {gps_location_socket}); PubMaster pm({"liveLocationKalman"}); uint64_t cnt = 0; @@ -717,8 +717,7 @@ int Localizer::locationd_thread() { filterInitialized = sm.allAliveAndValid(); } - // 100Hz publish for notcars, 20Hz for cars - const char* trigger_msg = sm["carParams"].getCarParams().getNotCar() ? "accelerometer" : "cameraOdometry"; + const char* trigger_msg = "cameraOdometry"; if (sm.updated(trigger_msg)) { bool inputsOK = sm.allValid() && this->are_inputs_ok(); bool gpsOK = this->is_gps_ok(); @@ -737,10 +736,7 @@ int Localizer::locationd_thread() { VectorXd posGeo = this->get_position_geodetic(); std::string lastGPSPosJSON = util::string_format( "{\"latitude\": %.15f, \"longitude\": %.15f, \"altitude\": %.15f}", posGeo(0), posGeo(1), posGeo(2)); - - std::thread([] (const std::string gpsjson) { - Params().put("LastGPSPosition", gpsjson); - }, lastGPSPosJSON).detach(); + params.putNonBlocking("LastGPSPosition", lastGPSPosJSON); } cnt++; } diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index b87c83cac2..9230cb48f0 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -7,7 +7,7 @@ import numpy as np from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY from openpilot.selfdrive.locationd.models.constants import ObservationKind -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from rednose.helpers.kalmanfilter import KalmanFilter diff --git a/selfdrive/locationd/models/gnss_helpers.py b/selfdrive/locationd/models/gnss_helpers.py deleted file mode 100644 index f412fafda9..0000000000 --- a/selfdrive/locationd/models/gnss_helpers.py +++ /dev/null @@ -1,35 +0,0 @@ -import numpy as np - - -# source: GNSSMeasurement (https://github.com/commaai/laika/blob/master/laika/raw_gnss.py) -class RawGNSSMeasurementIndices: - PRN = 0 - RECV_TIME_WEEK = 1 - RECV_TIME_SEC = 2 - GLONASS_FREQ = 3 - - PR = 4 - PR_STD = 5 - PRR = 6 - PRR_STD = 7 - - SAT_POS = slice(8, 11) - SAT_VEL = slice(11, 14) - - -def parse_prr(m): - sat_pos_vel_i = np.concatenate((m[RawGNSSMeasurementIndices.SAT_POS], - m[RawGNSSMeasurementIndices.SAT_VEL])) - R_i = np.atleast_2d(m[RawGNSSMeasurementIndices.PRR_STD]**2) - z_i = m[RawGNSSMeasurementIndices.PRR] - return z_i, R_i, sat_pos_vel_i - - -def parse_pr(m): - pseudorange = m[RawGNSSMeasurementIndices.PR] - pseudorange_stdev = m[RawGNSSMeasurementIndices.PR_STD] - sat_pos_freq_i = np.concatenate((m[RawGNSSMeasurementIndices.SAT_POS], - np.array([m[RawGNSSMeasurementIndices.GLONASS_FREQ]]))) - z_i = np.atleast_1d(pseudorange) - R_i = np.atleast_2d(pseudorange_stdev**2) - return z_i, R_i, sat_pos_freq_i diff --git a/selfdrive/locationd/models/gnss_kf.py b/selfdrive/locationd/models/gnss_kf.py deleted file mode 100755 index c4f3b2e210..0000000000 --- a/selfdrive/locationd/models/gnss_kf.py +++ /dev/null @@ -1,190 +0,0 @@ -#!/usr/bin/env python3 -import sys -from typing import List - -import numpy as np - -from openpilot.selfdrive.locationd.models.constants import ObservationKind -from openpilot.selfdrive.locationd.models.gnss_helpers import parse_pr, parse_prr - -if __name__ == '__main__': # Generating sympy - import sympy as sp - from rednose.helpers.ekf_sym import gen_code -else: - from rednose.helpers.ekf_sym_pyx import EKF_sym_pyx - from rednose.helpers.ekf_sym import EKF_sym - - -class States(): - ECEF_POS = slice(0, 3) # x, y and z in ECEF in meters - ECEF_VELOCITY = slice(3, 6) - CLOCK_BIAS = slice(6, 7) # clock bias in light-meters, - CLOCK_DRIFT = slice(7, 8) # clock drift in light-meters/s, - CLOCK_ACCELERATION = slice(8, 9) # clock acceleration in light-meters/s**2 - GLONASS_BIAS = slice(9, 10) # clock drift in light-meters/s, - GLONASS_FREQ_SLOPE = slice(10, 11) # GLONASS bias in m expressed as bias + freq_num*freq_slope - - -class GNSSKalman(): - name = 'gnss' - - x_initial = np.array([-2712700.6008, -4281600.6679, 3859300.1830, - 0, 0, 0, - 0, 0, 0, - 0, 0]) - - # state covariance - P_initial = np.diag([1e16, 1e16, 1e16, - 10**2, 10**2, 10**2, - 1e14, (100)**2, (0.2)**2, - (10)**2, (1)**2]) - - maha_test_kinds: List[int] = [] # ObservationKind.PSEUDORANGE_RATE, ObservationKind.PSEUDORANGE, ObservationKind.PSEUDORANGE_GLONASS] - - @staticmethod - def generate_code(generated_dir): - dim_state = GNSSKalman.x_initial.shape[0] - name = GNSSKalman.name - maha_test_kinds = GNSSKalman.maha_test_kinds - - # make functions and jacobians with sympy - # state variables - state_sym = sp.MatrixSymbol('state', dim_state, 1) - state = sp.Matrix(state_sym) - x, y, z = state[0:3, :] - v = state[3:6, :] - vx, vy, vz = v - cb, cd, ca = state[6:9, :] - glonass_bias, glonass_freq_slope = state[9:11, :] - - dt = sp.Symbol('dt') - - state_dot = sp.Matrix(np.zeros((dim_state, 1))) - state_dot[:3, :] = v - state_dot[6, 0] = cd - state_dot[7, 0] = ca - - # Basic descretization, 1st order integrator - # Can be pretty bad if dt is big - f_sym = state + dt * state_dot - - # - # Observation functions - # - - # extra args - sat_pos_freq_sym = sp.MatrixSymbol('sat_pos', 4, 1) - sat_pos_vel_sym = sp.MatrixSymbol('sat_pos_vel', 6, 1) - # sat_los_sym = sp.MatrixSymbol('sat_los', 3, 1) - # orb_epos_sym = sp.MatrixSymbol('orb_epos_sym', 3, 1) - - # expand extra args - sat_x, sat_y, sat_z, glonass_freq = sat_pos_freq_sym - sat_vx, sat_vy, sat_vz = sat_pos_vel_sym[3:] - # los_x, los_y, los_z = sat_los_sym - # orb_x, orb_y, orb_z = orb_epos_sym - - h_pseudorange_sym = sp.Matrix([ - sp.sqrt( - (x - sat_x)**2 + - (y - sat_y)**2 + - (z - sat_z)**2 - ) + cb - ]) - - h_pseudorange_glonass_sym = sp.Matrix([ - sp.sqrt( - (x - sat_x)**2 + - (y - sat_y)**2 + - (z - sat_z)**2 - ) + cb + glonass_bias + glonass_freq_slope * glonass_freq - ]) - - los_vector = (sp.Matrix(sat_pos_vel_sym[0:3]) - sp.Matrix([x, y, z])) - los_vector = los_vector / sp.sqrt(los_vector[0]**2 + los_vector[1]**2 + los_vector[2]**2) - h_pseudorange_rate_sym = sp.Matrix([los_vector[0] * (sat_vx - vx) + - los_vector[1] * (sat_vy - vy) + - los_vector[2] * (sat_vz - vz) + - cd]) - - obs_eqs = [[h_pseudorange_sym, ObservationKind.PSEUDORANGE_GPS, sat_pos_freq_sym], - [h_pseudorange_glonass_sym, ObservationKind.PSEUDORANGE_GLONASS, sat_pos_freq_sym], - [h_pseudorange_rate_sym, ObservationKind.PSEUDORANGE_RATE_GPS, sat_pos_vel_sym], - [h_pseudorange_rate_sym, ObservationKind.PSEUDORANGE_RATE_GLONASS, sat_pos_vel_sym]] - - gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, maha_test_kinds=maha_test_kinds) - - def __init__(self, generated_dir, cython=False, erratic_clock=False): - # process noise - clock_error_drift = 100.0 if erratic_clock else 0.1 - self.Q = np.diag([0.03**2, 0.03**2, 0.03**2, - 3**2, 3**2, 3**2, - (clock_error_drift)**2, (0)**2, (0.005)**2, - .1**2, (.01)**2]) - - self.dim_state = self.x_initial.shape[0] - - # init filter - filter_cls = EKF_sym_pyx if cython else EKF_sym - self.filter = filter_cls(generated_dir, self.name, self.Q, self.x_initial, self.P_initial, self.dim_state, - self.dim_state, maha_test_kinds=self.maha_test_kinds) - self.init_state(GNSSKalman.x_initial, covs=GNSSKalman.P_initial) - - @property - def x(self): - return self.filter.state() - - @property - def P(self): - return self.filter.covs() - - def predict(self, t): - return self.filter.predict(t) - - def rts_smooth(self, estimates): - return self.filter.rts_smooth(estimates, norm_quats=False) - - def init_state(self, state, covs_diag=None, covs=None, filter_time=None): - if covs_diag is not None: - P = np.diag(covs_diag) - elif covs is not None: - P = covs - else: - P = self.filter.covs() - self.filter.init_state(state, P, filter_time) - - def predict_and_observe(self, t, kind, data): - if len(data) > 0: - data = np.atleast_2d(data) - if kind == ObservationKind.PSEUDORANGE_GPS or kind == ObservationKind.PSEUDORANGE_GLONASS: - r = self.predict_and_update_pseudorange(data, t, kind) - elif kind == ObservationKind.PSEUDORANGE_RATE_GPS or kind == ObservationKind.PSEUDORANGE_RATE_GLONASS: - r = self.predict_and_update_pseudorange_rate(data, t, kind) - return r - - def predict_and_update_pseudorange(self, meas, t, kind): - R = np.zeros((len(meas), 1, 1)) - sat_pos_freq = np.zeros((len(meas), 4)) - z = np.zeros((len(meas), 1)) - for i, m in enumerate(meas): - z_i, R_i, sat_pos_freq_i = parse_pr(m) - sat_pos_freq[i, :] = sat_pos_freq_i - z[i, :] = z_i - R[i, :, :] = R_i - return self.filter.predict_and_update_batch(t, kind, z, R, sat_pos_freq) - - def predict_and_update_pseudorange_rate(self, meas, t, kind): - R = np.zeros((len(meas), 1, 1)) - z = np.zeros((len(meas), 1)) - sat_pos_vel = np.zeros((len(meas), 6)) - for i, m in enumerate(meas): - z_i, R_i, sat_pos_vel_i = parse_prr(m) - sat_pos_vel[i] = sat_pos_vel_i - R[i, :, :] = R_i - z[i, :] = z_i - return self.filter.predict_and_update_batch(t, kind, z, R, sat_pos_vel) - - -if __name__ == "__main__": - generated_dir = sys.argv[2] - GNSSKalman.generate_code(generated_dir) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 0e779c9e3e..d124eb5f05 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -7,12 +7,12 @@ import numpy as np import cereal.messaging as messaging from cereal import car from cereal import log -from openpilot.common.params import Params, put_nonblocking +from openpilot.common.params import Params from openpilot.common.realtime import config_realtime_process, DT_MDL from openpilot.common.numpy_fast import clip from openpilot.selfdrive.locationd.models.car_kf import CarKalman, ObservationKind, States from openpilot.selfdrive.locationd.models.constants import GENERATED_DIR -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog MAX_ANGLE_OFFSET_DELTA = 20 * DT_MDL # Max 20 deg/s @@ -124,7 +124,7 @@ def main(): REPLAY = bool(int(os.getenv("REPLAY", "0"))) pm = messaging.PubMaster(['liveParameters']) - sm = messaging.SubMaster(['liveLocationKalman', 'carState'], poll=['liveLocationKalman']) + sm = messaging.SubMaster(['liveLocationKalman', 'carState'], poll='liveLocationKalman') params_reader = Params() # wait for stats about the car to come in from controls @@ -251,7 +251,7 @@ def main(): 'stiffnessFactor': liveParameters.stiffnessFactor, 'angleOffsetAverageDeg': liveParameters.angleOffsetAverageDeg, } - put_nonblocking("LiveParameters", json.dumps(params)) + params_reader.put_nonblocking("LiveParameters", json.dumps(params)) pm.send('liveParameters', msg) diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index ff1fac2c22..69bab8d1fa 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -1,18 +1,15 @@ #!/usr/bin/env python3 -import os -import signal import numpy as np from collections import deque, defaultdict -from functools import partial import cereal.messaging as messaging from cereal import car, log from openpilot.common.params import Params from openpilot.common.realtime import config_realtime_process, DT_MDL from openpilot.common.filter_simple import FirstOrderFilter -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY -from openpilot.selfdrive.locationd.helpers import PointBuckets, ParameterEstimator, cache_points_onexit +from openpilot.selfdrive.locationd.helpers import PointBuckets, ParameterEstimator HISTORY = 5 # secs POINTS_PER_BUCKET = 1500 @@ -187,23 +184,23 @@ class TorqueEstimator(ParameterEstimator): liveTorqueParameters.version = VERSION liveTorqueParameters.useParams = self.use_params - if self.filtered_points.is_valid(): + # Calculate raw estimates when possible, only update filters when enough points are gathered + if self.filtered_points.is_calculable(): latAccelFactor, latAccelOffset, frictionCoeff = self.estimate_params() liveTorqueParameters.latAccelFactorRaw = float(latAccelFactor) liveTorqueParameters.latAccelOffsetRaw = float(latAccelOffset) liveTorqueParameters.frictionCoefficientRaw = float(frictionCoeff) - if any(val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, frictionCoeff]): - cloudlog.exception("Live torque parameters are invalid.") - liveTorqueParameters.liveValid = False - self.reset() - else: - liveTorqueParameters.liveValid = True - latAccelFactor = np.clip(latAccelFactor, self.min_lataccel_factor, self.max_lataccel_factor) - frictionCoeff = np.clip(frictionCoeff, self.min_friction, self.max_friction) - self.update_params({'latAccelFactor': latAccelFactor, 'latAccelOffset': latAccelOffset, 'frictionCoefficient': frictionCoeff}) - else: - liveTorqueParameters.liveValid = False + if self.filtered_points.is_valid(): + if any(val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, frictionCoeff]): + cloudlog.exception("Live torque parameters are invalid.") + liveTorqueParameters.liveValid = False + self.reset() + else: + liveTorqueParameters.liveValid = True + latAccelFactor = np.clip(latAccelFactor, self.min_lataccel_factor, self.max_lataccel_factor) + frictionCoeff = np.clip(frictionCoeff, self.min_friction, self.max_friction) + self.update_params({'latAccelFactor': latAccelFactor, 'latAccelOffset': latAccelOffset, 'frictionCoefficient': frictionCoeff}) if with_points: liveTorqueParameters.points = self.filtered_points.get_points()[:, [0, 2]].tolist() @@ -217,19 +214,16 @@ class TorqueEstimator(ParameterEstimator): return msg -def main(): +def main(demo=False): config_realtime_process([0, 1, 2, 3], 5) pm = messaging.PubMaster(['liveTorqueParameters']) - sm = messaging.SubMaster(['carControl', 'carState', 'liveLocationKalman'], poll=['liveLocationKalman']) + sm = messaging.SubMaster(['carControl', 'carState', 'liveLocationKalman'], poll='liveLocationKalman') params = Params() with car.CarParams.from_bytes(params.get("CarParams", block=True)) as CP: estimator = TorqueEstimator(CP) - if "REPLAY" not in os.environ: - signal.signal(signal.SIGINT, partial(cache_points_onexit, "LiveTorqueParameters", estimator)) - while True: sm.update() if sm.all_checks(): @@ -242,6 +236,14 @@ def main(): if sm.frame % 5 == 0: pm.send('liveTorqueParameters', estimator.get_msg(valid=sm.all_checks())) + # Cache points every 60 seconds while onroad + if sm.frame % 240 == 0: + msg = estimator.get_msg(valid=sm.all_checks(), with_points=True) + params.put_nonblocking("LiveTorqueParameters", msg.to_bytes()) if __name__ == "__main__": - main() + import argparse + parser = argparse.ArgumentParser(description='Process the --demo argument.') + parser.add_argument('--demo', action='store_true', help='A boolean for demo mode.') + args = parser.parse_args() + main(demo=args.demo) diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 247f3c8fb8..f2758cf32b 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -9,7 +9,7 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.spinner import Spinner from openpilot.common.text_window import TextWindow from openpilot.system.hardware import AGNOS -from openpilot.system.swaglog import cloudlog, add_file_handler +from openpilot.common.swaglog import cloudlog, add_file_handler from openpilot.system.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 @@ -17,7 +17,6 @@ CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") TOTAL_SCONS_NODES = 2560 MAX_BUILD_PROGRESS = 100 -PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: env = os.environ.copy() @@ -85,7 +84,7 @@ def build(spinner: Spinner, dirty: bool = False, minimal: bool = False) -> None: f.unlink() -if __name__ == "__main__" and not PREBUILT: +if __name__ == "__main__": spinner = Spinner() spinner.update_progress(0, 100) build(spinner, is_dirty(), minimal = AGNOS) diff --git a/selfdrive/manager/helpers.py b/selfdrive/manager/helpers.py index f8607fffc6..047d0ac2d6 100644 --- a/selfdrive/manager/helpers.py +++ b/selfdrive/manager/helpers.py @@ -1,9 +1,16 @@ +import errno +import fcntl import os import sys -import fcntl -import errno +import pathlib +import shutil import signal +import subprocess +import tempfile +import threading +from openpilot.common.basedir import BASEDIR +from openpilot.common.params import Params def unblock_stdout() -> None: # get a non-blocking stdout @@ -41,3 +48,20 @@ def unblock_stdout() -> None: def write_onroad_params(started, params): params.put_bool("IsOnroad", started) params.put_bool("IsOffroad", not started) + + +def save_bootlog(): + # copy current params + tmp = tempfile.mkdtemp() + params_dirname = pathlib.Path(Params().get_param_path()).name + params_dir = os.path.join(tmp, params_dirname) + shutil.copytree(Params().get_param_path(), params_dir, dirs_exist_ok=True) + + def fn(tmpdir): + env = os.environ.copy() + env['PARAMS_COPY_PATH'] = tmpdir + subprocess.call("./bootlog", cwd=os.path.join(BASEDIR, "system/loggerd"), env=env) + shutil.rmtree(tmpdir) + t = threading.Thread(target=fn, args=(tmp, )) + t.daemon = True + t.start() diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index a739437de7..bf1eeb8fd0 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -2,7 +2,6 @@ import datetime import os import signal -import subprocess import sys import traceback from typing import List, Tuple, Union @@ -10,33 +9,29 @@ from typing import List, Tuple, Union from cereal import log import cereal.messaging as messaging import openpilot.selfdrive.sentry as sentry -from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params, ParamKeyType from openpilot.common.text_window import TextWindow -from openpilot.selfdrive.boardd.set_time import set_time from openpilot.system.hardware import HARDWARE, PC -from openpilot.selfdrive.manager.helpers import unblock_stdout, write_onroad_params +from openpilot.selfdrive.manager.helpers import unblock_stdout, write_onroad_params, save_bootlog from openpilot.selfdrive.manager.process import ensure_running from openpilot.selfdrive.manager.process_config import managed_processes from openpilot.selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID -from openpilot.system.swaglog import cloudlog, add_file_handler +from openpilot.common.swaglog import cloudlog, add_file_handler from openpilot.system.version import is_dirty, get_commit, get_version, get_origin, get_short_branch, \ get_normalized_origin, terms_version, training_version, \ - is_tested_branch, is_release_branch + is_tested_branch, is_release_branch, get_commit_date def manager_init() -> None: - # update system time from panda - set_time(cloudlog) - - # save boot log - subprocess.call("./bootlog", cwd=os.path.join(BASEDIR, "system/loggerd")) + save_bootlog() params = Params() params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START) params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION) params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) + if is_release_branch(): + params.clear_all(ParamKeyType.DEVELOPMENT_ONLY) default_params: List[Tuple[str, Union[str, bytes]]] = [ ("CompletedTrainingVersion", "0"), @@ -58,13 +53,6 @@ def manager_init() -> None: if params.get(k) is None: params.put(k, v) - # is this dashcam? - if os.getenv("PASSIVE") is not None: - params.put_bool("Passive", bool(int(os.getenv("PASSIVE", "0")))) - - if params.get("Passive") is None: - raise Exception("Passive must be set to continue") - # Create folders needed for msgq try: os.mkdir("/dev/shm") @@ -77,9 +65,10 @@ def manager_init() -> None: params.put("Version", get_version()) params.put("TermsVersion", terms_version) params.put("TrainingVersion", training_version) - params.put("GitCommit", get_commit(default="")) - params.put("GitBranch", get_short_branch(default="")) - params.put("GitRemote", get_origin(default="")) + params.put("GitCommit", get_commit()) + params.put("GitCommitDate", get_commit_date()) + params.put("GitBranch", get_short_branch()) + params.put("GitRemote", get_origin()) params.put_bool("IsTestedBranch", is_tested_branch()) params.put_bool("IsReleaseBranch", is_release_branch()) @@ -91,6 +80,9 @@ def manager_init() -> None: serial = params.get("HardwareSerial") raise Exception(f"Registration failed for device {serial}") os.environ['DONGLE_ID'] = dongle_id # Needed for swaglog + os.environ['GIT_ORIGIN'] = get_normalized_origin() # Needed for swaglog + os.environ['GIT_BRANCH'] = get_short_branch() # Needed for swaglog + os.environ['GIT_COMMIT'] = get_commit() # Needed for swaglog if not is_dirty(): os.environ['CLEAN'] = '1' @@ -105,8 +97,7 @@ def manager_init() -> None: dirty=is_dirty(), device=HARDWARE.get_device_type()) - -def manager_prepare() -> None: + # preimport all processes for p in managed_processes.values(): p.prepare() @@ -137,7 +128,7 @@ def manager_thread() -> None: ignore.append("pandad") ignore += [x for x in os.getenv("BLOCK", "").split(",") if len(x) > 0] - sm = messaging.SubMaster(['deviceState', 'carParams'], poll=['deviceState']) + sm = messaging.SubMaster(['deviceState', 'carParams'], poll='deviceState') pm = messaging.PubMaster(['managerState']) write_onroad_params(False, params) @@ -146,7 +137,7 @@ def manager_thread() -> None: started_prev = False while True: - sm.update() + sm.update(1000) started = sm['deviceState'].started @@ -169,7 +160,7 @@ def manager_thread() -> None: cloudlog.debug(running) # send managerState - msg = messaging.new_message('managerState') + msg = messaging.new_message('managerState', valid=True) msg.managerState.processes = [p.get_process_state_msg() for p in managed_processes.values()] pm.send('managerState', msg) @@ -186,17 +177,8 @@ def manager_thread() -> None: def main() -> None: - prepare_only = os.getenv("PREPAREONLY") is not None - manager_init() - - # Start UI early so prepare can happen in the background - if not prepare_only: - managed_processes['ui'].start() - - manager_prepare() - - if prepare_only: + if os.getenv("PREPAREONLY") is not None: return # SystemExit on sigterm @@ -227,6 +209,8 @@ if __name__ == "__main__": try: main() + except KeyboardInterrupt: + print("got CTRL-C, exiting") except Exception: add_file_handler(cloudlog) cloudlog.exception("Manager failed to start") diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index 82cc8d74a3..ac1b4ac68c 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -15,7 +15,7 @@ import cereal.messaging as messaging import openpilot.selfdrive.sentry as sentry from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog WATCHDOG_FN = "/dev/shm/wd_" ENABLE_WATCHDOG = os.getenv("NO_WATCHDOG") is None @@ -281,11 +281,13 @@ def ensure_running(procs: ValuesView[ManagerProcess], started: bool, params=None running = [] for p in procs: if p.enabled and p.name not in not_run and p.should_run(started, params, CP): - p.start() running.append(p) else: p.stop(block=False) p.check_watchdog(started) + for p in running: + p.start() + return running diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 320958d344..cb6dd8883f 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -49,7 +49,7 @@ procs = [ NativeProcess("proclogd", "system/proclogd", ["./proclogd"], only_onroad), PythonProcess("logmessaged", "system.logmessaged", always_run), PythonProcess("micd", "system.micd", iscar), - PythonProcess("timezoned", "system.timezoned", always_run, enabled=not PC), + PythonProcess("timed", "system.timed", always_run, enabled=not PC), PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)), NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad), @@ -60,7 +60,7 @@ procs = [ PythonProcess("navmodeld", "selfdrive.modeld.navmodeld", only_onroad), NativeProcess("sensord", "system/sensord", ["./sensord"], only_onroad, enabled=not PC), NativeProcess("ui", "selfdrive/ui", ["./ui"], always_run, watchdog_max_dt=(5 if not PC else None)), - NativeProcess("soundd", "selfdrive/ui/soundd", ["./soundd"], only_onroad), + PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad), NativeProcess("locationd", "selfdrive/locationd", ["./locationd"], only_onroad), NativeProcess("boardd", "selfdrive/boardd", ["./boardd"], always_run, enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), @@ -68,7 +68,7 @@ procs = [ PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(not PC or WEBCAM)), - PythonProcess("rawgpsd", "system.sensord.rawgps.rawgpsd", qcomgps, enabled=TICI), + PythonProcess("qcomgpsd", "system.qcomgpsd.qcomgpsd", qcomgps, enabled=TICI), PythonProcess("navd", "selfdrive.navd.navd", only_onroad), PythonProcess("pandad", "selfdrive.boardd.pandad", always_run), PythonProcess("paramsd", "selfdrive.locationd.paramsd", only_onroad), @@ -84,6 +84,7 @@ procs = [ # debug procs NativeProcess("bridge", "cereal/messaging", ["./bridge"], notcar), + PythonProcess("webrtcd", "system.webrtc.webrtcd", notcar), PythonProcess("webjoystick", "tools.bodyteleop.web", notcar), ] diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py index 0fa186baff..1ae94b26a1 100755 --- a/selfdrive/manager/test/test_manager.py +++ b/selfdrive/manager/test/test_manager.py @@ -5,6 +5,8 @@ import signal import time import unittest +from parameterized import parameterized + from cereal import car from openpilot.common.params import Params import openpilot.selfdrive.manager.manager as manager @@ -21,7 +23,6 @@ BLACKLIST_PROCS = ['manage_athenad', 'pandad', 'pigeond'] @pytest.mark.tici class TestManager(unittest.TestCase): def setUp(self): - os.environ['PASSIVE'] = '0' HARDWARE.set_power_save(False) # ensure clean CarParams @@ -39,21 +40,21 @@ class TestManager(unittest.TestCase): # TODO: ensure there are blacklisted procs until we have a dedicated test self.assertTrue(len(BLACKLIST_PROCS), "No blacklisted procs to test not_run") - def test_startup_time(self): - for _ in range(10): - start = time.monotonic() - os.environ['PREPAREONLY'] = '1' - manager.main() - t = time.monotonic() - start - assert t < MAX_STARTUP_TIME, f"startup took {t}s, expected <{MAX_STARTUP_TIME}s" + @parameterized.expand([(i,) for i in range(10)]) + def test_startup_time(self, index): + start = time.monotonic() + os.environ['PREPAREONLY'] = '1' + manager.main() + t = time.monotonic() - start + assert t < MAX_STARTUP_TIME, f"startup took {t}s, expected <{MAX_STARTUP_TIME}s" + @unittest.skip("this test is flaky the way it's currently written, should be moved to test_onroad") def test_clean_exit(self): """ Ensure all processes exit cleanly when stopped. """ HARDWARE.set_power_save(False) manager.manager_init() - manager.manager_prepare() CP = car.CarParams.new_message() procs = ensure_running(managed_processes.values(), True, Params(), CP, not_run=BLACKLIST_PROCS) diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index 4d3af51635..dda1ff5e33 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -22,6 +22,8 @@ class ModelConstants: NAV_INSTRUCTION_LEN = 150 DRIVING_STYLE_LEN = 12 LAT_PLANNER_STATE_LEN = 4 + LATERAL_CONTROL_PARAMS_LEN = 2 + PREV_DESIRED_CURV_LEN = 1 # model outputs constants FCW_THRESHOLDS_5MS2 = np.array([.05, .05, .15, .15, .15], dtype=np.float32) @@ -39,6 +41,7 @@ class ModelConstants: PLAN_WIDTH = 15 DESIRE_PRED_WIDTH = 8 LAT_PLANNER_SOLUTION_WIDTH = 4 + DESIRED_CURV_WIDTH = 1 NUM_LANE_LINES = 4 NUM_ROAD_EDGES = 2 diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index 53c0af0ff3..1e25964702 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -11,7 +11,7 @@ from typing import Tuple, Dict from cereal import messaging from cereal.messaging import PubMaster, SubMaster from cereal.visionipc import VisionIpcClient, VisionStreamType, VisionBuf -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime @@ -101,7 +101,7 @@ def fill_driver_state(msg, ds_result: DriverStateResult): def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float): model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(DMonitoringModelResult)).contents - msg = messaging.new_message('driverStateV2') + msg = messaging.new_message('driverStateV2', valid=True) ds = msg.driverStateV2 ds.frameId = frame_id ds.modelExecutionTime = execution_time diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index 7434e94287..c76966867a 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -72,9 +72,8 @@ def fill_model_msg(msg: capnp._DynamicStructBuilder, net_output_data: Dict[str, fill_xyzt(orientation_rate, ModelConstants.T_IDXS, *net_output_data['plan'][0,:,Plan.ORIENTATION_RATE].T) # lateral planning - solution = modelV2.lateralPlannerSolution - solution.x, solution.y, solution.yaw, solution.yawRate = [net_output_data['lat_planner_solution'][0,:,i].tolist() for i in range(4)] - solution.xStd, solution.yStd, solution.yawStd, solution.yawRateStd = [net_output_data['lat_planner_solution_stds'][0,:,i].tolist() for i in range(4)] + action = modelV2.action + action.desiredCurvature = float(net_output_data['desired_curvature'][0,0]) # times at X_IDXS according to model plan PLAN_T_IDXS = [np.nan] * ModelConstants.IDX_N diff --git a/selfdrive/modeld/modeld b/selfdrive/modeld/modeld index 14048ec9fd..e1cef4dcc3 100755 --- a/selfdrive/modeld/modeld +++ b/selfdrive/modeld/modeld @@ -7,4 +7,4 @@ if [ -f "$DIR/libthneed.so" ]; then export LD_PRELOAD="$DIR/libthneed.so" fi -exec "$DIR/modeld.py" +exec "$DIR/modeld.py" "$@" diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 2b211b22e6..f2842d94b7 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -4,19 +4,20 @@ import time import pickle import numpy as np import cereal.messaging as messaging +from cereal import car, log from pathlib import Path from typing import Dict, Optional from setproctitle import setproctitle from cereal.messaging import PubMaster, SubMaster from cereal.visionipc import VisionIpcClient, VisionStreamType, VisionBuf -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params -from openpilot.common.realtime import DT_MDL -from openpilot.common.numpy_fast import interp from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.realtime import config_realtime_process from openpilot.common.transformations.model import get_warp_matrix from openpilot.selfdrive import sentry +from openpilot.selfdrive.car.car_helpers import get_demo_car_params +from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime from openpilot.selfdrive.modeld.parse_model_outputs import Parser from openpilot.selfdrive.modeld.fill_model_msg import fill_model_msg, fill_pose_msg, PublishState @@ -56,7 +57,8 @@ class ModelState: self.inputs = { 'desire': np.zeros(ModelConstants.DESIRE_LEN * (ModelConstants.HISTORY_BUFFER_LEN+1), dtype=np.float32), 'traffic_convention': np.zeros(ModelConstants.TRAFFIC_CONVENTION_LEN, dtype=np.float32), - 'lat_planner_state': np.zeros(ModelConstants.LAT_PLANNER_STATE_LEN, dtype=np.float32), + 'lateral_control_params': np.zeros(ModelConstants.LATERAL_CONTROL_PARAMS_LEN, dtype=np.float32), + 'prev_desired_curv': np.zeros(ModelConstants.PREV_DESIRED_CURV_LEN * (ModelConstants.HISTORY_BUFFER_LEN+1), dtype=np.float32), 'nav_features': np.zeros(ModelConstants.NAV_FEATURE_LEN, dtype=np.float32), 'nav_instructions': np.zeros(ModelConstants.NAV_INSTRUCTION_LEN, dtype=np.float32), 'features_buffer': np.zeros(ModelConstants.HISTORY_BUFFER_LEN * ModelConstants.FEATURE_LEN, dtype=np.float32), @@ -91,9 +93,9 @@ class ModelState: self.prev_desire[:] = inputs['desire'] self.inputs['traffic_convention'][:] = inputs['traffic_convention'] + self.inputs['lateral_control_params'][:] = inputs['lateral_control_params'] self.inputs['nav_features'][:] = inputs['nav_features'] self.inputs['nav_instructions'][:] = inputs['nav_instructions'] - # self.inputs['driving_style'][:] = inputs['driving_style'] # if getCLBuffer is not None, frame will be None self.model.setInputBuffer("input_imgs", self.frame.prepare(buf, transform.flatten(), self.model.getCLBuffer("input_imgs"))) @@ -108,18 +110,22 @@ class ModelState: self.inputs['features_buffer'][:-ModelConstants.FEATURE_LEN] = self.inputs['features_buffer'][ModelConstants.FEATURE_LEN:] self.inputs['features_buffer'][-ModelConstants.FEATURE_LEN:] = outputs['hidden_state'][0, :] - self.inputs['lat_planner_state'][2] = interp(DT_MDL, ModelConstants.T_IDXS, outputs['lat_planner_solution'][0, :, 2]) - self.inputs['lat_planner_state'][3] = interp(DT_MDL, ModelConstants.T_IDXS, outputs['lat_planner_solution'][0, :, 3]) + self.inputs['prev_desired_curv'][:-ModelConstants.PREV_DESIRED_CURV_LEN] = self.inputs['prev_desired_curv'][ModelConstants.PREV_DESIRED_CURV_LEN:] + self.inputs['prev_desired_curv'][-ModelConstants.PREV_DESIRED_CURV_LEN:] = outputs['desired_curvature'][0, :] return outputs -def main(): +def main(demo=False): + cloudlog.warning("modeld init") + sentry.set_tag("daemon", PROCESS_NAME) cloudlog.bind(daemon=PROCESS_NAME) setproctitle(PROCESS_NAME) config_realtime_process(7, 54) + cloudlog.warning("setting up CL context") cl_context = CLContext() + cloudlog.warning("CL context ready; loading model") model = ModelState(cl_context) cloudlog.warning("models loaded, modeld starting") @@ -148,7 +154,7 @@ def main(): # messaging pm = PubMaster(["modelV2", "cameraOdometry"]) - sm = SubMaster(["lateralPlan", "roadCameraState", "liveCalibration", "driverMonitoringState", "navModel", "navInstruction"]) + sm = SubMaster(["carState", "roadCameraState", "liveCalibration", "driverMonitoringState", "navModel", "navInstruction", "carControl"]) publish_state = PublishState() params = Params() @@ -162,13 +168,25 @@ def main(): model_transform_main = np.zeros((3, 3), dtype=np.float32) model_transform_extra = np.zeros((3, 3), dtype=np.float32) live_calib_seen = False - driving_style = np.array([1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0], dtype=np.float32) nav_features = np.zeros(ModelConstants.NAV_FEATURE_LEN, dtype=np.float32) nav_instructions = np.zeros(ModelConstants.NAV_INSTRUCTION_LEN, dtype=np.float32) buf_main, buf_extra = None, None meta_main = FrameMeta() meta_extra = FrameMeta() + + if demo: + CP = get_demo_car_params() + else: + with car.CarParams.from_bytes(params.get("CarParams", block=True)) as msg: + CP = msg + cloudlog.info("modeld got CarParams: %s", CP.carName) + + # TODO this needs more thought, use .2s extra for now to estimate other delays + steer_delay = CP.steerActuatorDelay + .2 + + DH = DesireHelper() + while True: # Keep receiving frames until we are at least 1 frame ahead of previous extra frame while meta_main.timestamp_sof < meta_extra.timestamp_sof + 25000000: @@ -203,11 +221,11 @@ def main(): buf_extra = buf_main meta_extra = meta_main - # TODO: path planner timeout? sm.update(0) - desire = sm["lateralPlan"].desire.raw + desire = DH.desire is_rhd = sm["driverMonitoringState"].isRHD frame_id = sm["roadCameraState"].frameId + lateral_control_params = np.array([sm["carState"].vEgo, steer_delay], dtype=np.float32) if sm.updated["liveCalibration"]: device_from_calib_euler = np.array(sm["liveCalibration"].rpyCalib, dtype=np.float32) model_transform_main = get_warp_matrix(device_from_calib_euler, main_wide_camera, False).astype(np.float32) @@ -261,7 +279,7 @@ def main(): inputs:Dict[str, np.ndarray] = { 'desire': vec_desire, 'traffic_convention': traffic_convention, - 'driving_style': driving_style, + 'lateral_control_params': lateral_control_params, 'nav_features': nav_features, 'nav_instructions': nav_instructions} @@ -276,6 +294,14 @@ def main(): fill_model_msg(modelv2_send, model_output, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id, frame_drop_ratio, meta_main.timestamp_eof, timestamp_llk, model_execution_time, nav_enabled, live_calib_seen) + desire_state = modelv2_send.modelV2.meta.desireState + l_lane_change_prob = desire_state[log.Desire.laneChangeLeft] + r_lane_change_prob = desire_state[log.Desire.laneChangeRight] + lane_change_prob = l_lane_change_prob + r_lane_change_prob + DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob) + modelv2_send.modelV2.meta.laneChangeState = DH.lane_change_state + modelv2_send.modelV2.meta.laneChangeDirection = DH.lane_change_direction + fill_pose_msg(posenet_send, model_output, meta_main.frame_id, vipc_dropped_frames, meta_main.timestamp_eof, live_calib_seen) pm.send('modelV2', modelv2_send) pm.send('cameraOdometry', posenet_send) @@ -285,7 +311,11 @@ def main(): if __name__ == "__main__": try: - main() + import argparse + parser = argparse.ArgumentParser() + parser.add_argument('--demo', action='store_true', help='A boolean for demo mode.') + args = parser.parse_args() + main(demo=args.demo) except KeyboardInterrupt: cloudlog.warning(f"child {PROCESS_NAME} got SIGINT") except Exception: diff --git a/selfdrive/modeld/models/commonmodel_pyx.pxd b/selfdrive/modeld/models/commonmodel_pyx.pxd index 21c0716de4..97e3914588 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pxd +++ b/selfdrive/modeld/models/commonmodel_pyx.pxd @@ -7,7 +7,7 @@ cdef class CLContext(BaseCLContext): pass cdef class CLMem: - cdef cl_mem * mem; + cdef cl_mem * mem @staticmethod cdef create(void*) diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc index 485009a997..7f911cb213 100644 Binary files a/selfdrive/modeld/models/dmonitoring_model_q.dlc and b/selfdrive/modeld/models/dmonitoring_model_q.dlc differ diff --git a/selfdrive/modeld/models/navmodel_q.dlc b/selfdrive/modeld/models/navmodel_q.dlc index a899829e3b..505d5c556f 100644 Binary files a/selfdrive/modeld/models/navmodel_q.dlc and b/selfdrive/modeld/models/navmodel_q.dlc differ diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 181c264b01..acd7490966 100644 Binary files a/selfdrive/modeld/models/supercombo.onnx and b/selfdrive/modeld/models/supercombo.onnx differ diff --git a/selfdrive/modeld/navmodeld.py b/selfdrive/modeld/navmodeld.py index 90b9762800..ed0b597dfe 100755 --- a/selfdrive/modeld/navmodeld.py +++ b/selfdrive/modeld/navmodeld.py @@ -10,7 +10,7 @@ from typing import Tuple, Dict from cereal import messaging from cereal.messaging import PubMaster, SubMaster from cereal.visionipc import VisionIpcClient, VisionStreamType -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.constants import ModelConstants diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index 9d37a5fad4..01cba29d1c 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -93,7 +93,10 @@ class Parser: self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,)) self.parse_mdn('lead', outs, in_N=ModelConstants.LEAD_MHP_N, out_N=ModelConstants.LEAD_MHP_SELECTION, out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_WIDTH)) - self.parse_mdn('lat_planner_solution', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N,ModelConstants.LAT_PLANNER_SOLUTION_WIDTH)) + if 'lat_planner_solution' in outs: + self.parse_mdn('lat_planner_solution', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N,ModelConstants.LAT_PLANNER_SOLUTION_WIDTH)) + if 'desired_curvature' in outs: + self.parse_mdn('desired_curvature', outs, in_N=0, out_N=0, out_shape=(ModelConstants.DESIRED_CURV_WIDTH,)) for k in ['lead_prob', 'lane_lines_prob', 'meta']: self.parse_binary_crossentropy(k, outs) self.parse_categorical_crossentropy('desire_state', outs, out_shape=(ModelConstants.DESIRE_PRED_WIDTH,)) diff --git a/selfdrive/modeld/runners/runmodel_pyx.pyx b/selfdrive/modeld/runners/runmodel_pyx.pyx index cdc62a79be..e1b201a6a9 100644 --- a/selfdrive/modeld/runners/runmodel_pyx.pyx +++ b/selfdrive/modeld/runners/runmodel_pyx.pyx @@ -2,7 +2,6 @@ # cython: c_string_encoding=ascii from libcpp.string cimport string -from libc.string cimport memcpy from .runmodel cimport USE_CPU_RUNTIME, USE_GPU_RUNTIME, USE_DSP_RUNTIME from selfdrive.modeld.models.commonmodel_pyx cimport CLMem diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index 6ed5c08e81..3dc2bef414 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -4,13 +4,14 @@ #include "third_party/json11/json11.hpp" #include "common/util.h" #include "common/clutil.h" +#include "common/swaglog.h" #include "selfdrive/modeld/thneed/thneed.h" using namespace json11; extern map g_program_source; void Thneed::load(const char *filename) { - printf("Thneed::load: loading from %s\n", filename); + LOGD("Thneed::load: loading from %s\n", filename); string buf = util::read_file(filename); int jsz = *(int *)buf.data(); @@ -74,8 +75,8 @@ void Thneed::load(const char *filename) { clbuf = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &errcode); #endif if (clbuf == NULL) { - printf("clError: %s create image %zux%zu rp %zu with buffer %p\n", cl_get_error_string(errcode), - desc.image_width, desc.image_height, desc.image_row_pitch, desc.buffer); + LOGE("clError: %s create image %zux%zu rp %zu with buffer %p\n", cl_get_error_string(errcode), + desc.image_width, desc.image_height, desc.image_row_pitch, desc.buffer); } assert(clbuf != NULL); } @@ -95,11 +96,11 @@ void Thneed::load(const char *filename) { cl_mem aa = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; input_clmem.push_back(aa); input_sizes.push_back(sz); - printf("Thneed::load: adding input %s with size %d\n", mobj["name"].string_value().data(), sz); + LOGD("Thneed::load: adding input %s with size %d\n", mobj["name"].string_value().data(), sz); cl_int cl_err; void *ret = clEnqueueMapBuffer(command_queue, aa, CL_TRUE, CL_MAP_WRITE, 0, sz, 0, NULL, NULL, &cl_err); - if (cl_err != CL_SUCCESS) printf("clError: %s map %p %d\n", cl_get_error_string(cl_err), aa, sz); + if (cl_err != CL_SUCCESS) LOGE("clError: %s map %p %d\n", cl_get_error_string(cl_err), aa, sz); assert(cl_err == CL_SUCCESS); inputs.push_back(ret); } @@ -107,7 +108,7 @@ void Thneed::load(const char *filename) { for (auto &obj : jdat["outputs"].array_items()) { auto mobj = obj.object_items(); int sz = mobj["size"].int_value(); - printf("Thneed::save: adding output with size %d\n", sz); + LOGD("Thneed::save: adding output with size %d\n", sz); // TODO: support multiple outputs output = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; assert(output != NULL); diff --git a/selfdrive/modeld/transforms/transform.cl b/selfdrive/modeld/transforms/transform.cl index 357ef87321..2ca25920cd 100644 --- a/selfdrive/modeld/transforms/transform.cl +++ b/selfdrive/modeld/transforms/transform.cl @@ -22,20 +22,20 @@ __kernel void warpPerspective(__global const uchar * src, W = W != 0.0f ? INTER_TAB_SIZE / W : 0.0f; int X = rint(X0 * W), Y = rint(Y0 * W); - short sx = convert_short_sat(X >> INTER_BITS); - short sy = convert_short_sat(Y >> INTER_BITS); + int sx = convert_short_sat(X >> INTER_BITS); + int sy = convert_short_sat(Y >> INTER_BITS); + + short sx_clamp = clamp(sx, 0, src_cols - 1); + short sx_p1_clamp = clamp(sx + 1, 0, src_cols - 1); + short sy_clamp = clamp(sy, 0, src_rows - 1); + short sy_p1_clamp = clamp(sy + 1, 0, src_rows - 1); + int v0 = convert_int(src[mad24(sy_clamp, src_row_stride, src_offset + sx_clamp*src_px_stride)]); + int v1 = convert_int(src[mad24(sy_clamp, src_row_stride, src_offset + sx_p1_clamp*src_px_stride)]); + int v2 = convert_int(src[mad24(sy_p1_clamp, src_row_stride, src_offset + sx_clamp*src_px_stride)]); + int v3 = convert_int(src[mad24(sy_p1_clamp, src_row_stride, src_offset + sx_p1_clamp*src_px_stride)]); + short ay = (short)(Y & (INTER_TAB_SIZE - 1)); short ax = (short)(X & (INTER_TAB_SIZE - 1)); - - int v0 = (sx >= 0 && sx < src_cols && sy >= 0 && sy < src_rows) ? - convert_int(src[mad24(sy, src_row_stride, src_offset + sx*src_px_stride)]) : 0; - int v1 = (sx+1 >= 0 && sx+1 < src_cols && sy >= 0 && sy < src_rows) ? - convert_int(src[mad24(sy, src_row_stride, src_offset + (sx+1)*src_px_stride)]) : 0; - int v2 = (sx >= 0 && sx < src_cols && sy+1 >= 0 && sy+1 < src_rows) ? - convert_int(src[mad24(sy+1, src_row_stride, src_offset + sx*src_px_stride)]) : 0; - int v3 = (sx+1 >= 0 && sx+1 < src_cols && sy+1 >= 0 && sy+1 < src_rows) ? - convert_int(src[mad24(sy+1, src_row_stride, src_offset + (sx+1)*src_px_stride)]) : 0; - float taby = 1.f/INTER_TAB_SIZE*ay; float tabx = 1.f/INTER_TAB_SIZE*ax; diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index ff2ee71e74..579e79093f 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -3,8 +3,7 @@ import gc import cereal.messaging as messaging from cereal import car -from cereal import log -from openpilot.common.params import Params, put_bool_nonblocking +from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.controls.lib.events import Events from openpilot.selfdrive.monitoring.driver_monitor import DriverStatus @@ -14,15 +13,11 @@ def dmonitoringd_thread(): gc.disable() set_realtime_priority(2) + params = Params() pm = messaging.PubMaster(['driverMonitoringState']) - sm = messaging.SubMaster(['driverStateV2', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll=['driverStateV2']) + sm = messaging.SubMaster(['driverStateV2', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll='driverStateV2') - driver_status = DriverStatus(rhd_saved=Params().get_bool("IsRhdDetected")) - - sm['liveCalibration'].calStatus = log.LiveCalibrationData.Status.invalid - sm['liveCalibration'].rpyCalib = [0, 0, 0] - sm['carState'].buttonEvents = [] - sm['carState'].standstill = True + driver_status = DriverStatus(rhd_saved=params.get_bool("IsRhdDetected")) v_cruise_last = 0 driver_engaged = False @@ -30,7 +25,6 @@ def dmonitoringd_thread(): # 10Hz <- dmonitoringmodeld while True: sm.update() - if not sm.updated['driverStateV2']: continue @@ -48,7 +42,9 @@ def dmonitoringd_thread(): # Get data from dmonitoringmodeld events = Events() - driver_status.update_states(sm['driverStateV2'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) + + if sm.all_checks() and len(sm['liveCalibration'].rpyCalib): + driver_status.update_states(sm['driverStateV2'], sm['liveCalibration'].rpyCalib, sm['carState'].vEgo, sm['controlsState'].enabled) # Block engaging after max number of distrations if driver_status.terminal_alert_cnt >= driver_status.settings._MAX_TERMINAL_ALERTS or \ @@ -59,7 +55,7 @@ def dmonitoringd_thread(): driver_status.update_events(events, driver_engaged, sm['controlsState'].enabled, sm['carState'].standstill) # build driverMonitoringState packet - dat = messaging.new_message('driverMonitoringState') + dat = messaging.new_message('driverMonitoringState', valid=sm.all_checks()) dat.driverMonitoringState = { "events": events.to_msg(), "faceDetected": driver_status.face_detected, @@ -84,7 +80,7 @@ def dmonitoringd_thread(): if (sm['driverStateV2'].frameId % 6000 == 0 and driver_status.wheelpos_learner.filtered_stat.n > driver_status.settings._WHEELPOS_FILTER_MIN_COUNT and driver_status.wheel_on_right == (driver_status.wheelpos_learner.filtered_stat.M > driver_status.settings._WHEELPOS_THRESHOLD)): - put_bool_nonblocking("IsRhdDetected", driver_status.wheel_on_right) + params.put_bool_nonblocking("IsRhdDetected", driver_status.wheel_on_right) def main(): dmonitoringd_thread() diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index ab82da301f..2279002f35 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -29,10 +29,10 @@ class DRIVER_MONITOR_SETTINGS(): self._FACE_THRESHOLD = 0.7 self._EYE_THRESHOLD = 0.65 self._SG_THRESHOLD = 0.9 - self._BLINK_THRESHOLD = 0.895 + self._BLINK_THRESHOLD = 0.865 - self._EE_THRESH11 = 0.275 - self._EE_THRESH12 = 5.5 + self._EE_THRESH11 = 0.241 + self._EE_THRESH12 = 4.7 self._EE_MAX_OFFSET1 = 0.06 self._EE_MIN_OFFSET1 = 0.025 self._EE_THRESH21 = 0.01 diff --git a/selfdrive/navd/SConscript b/selfdrive/navd/SConscript index c116ef1535..5a173c0351 100644 --- a/selfdrive/navd/SConscript +++ b/selfdrive/navd/SConscript @@ -1,14 +1,14 @@ Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'transformations') map_env = qt_env.Clone() -libs = ['qt_widgets', 'qt_util', 'qmapboxgl', common, messaging, cereal, visionipc, transformations, +libs = ['qt_widgets', 'qt_util', 'QMapLibre', common, messaging, cereal, visionipc, transformations, 'zmq', 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread', 'json11'] + map_env["LIBS"] if arch == 'larch64': libs.append(':libEGL_mesa.so.0') if arch in ['larch64', 'aarch64', 'x86_64']: if arch == 'x86_64': - rpath = Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath + rpath = Dir(f"#third_party/maplibre-native-qt/{arch}/lib").srcnode().abspath map_env["RPATH"] += [rpath, ] style_path = File("style.json").abspath diff --git a/selfdrive/navd/main.cc b/selfdrive/navd/main.cc index 5251b046fb..2e7b4d3b60 100644 --- a/selfdrive/navd/main.cc +++ b/selfdrive/navd/main.cc @@ -11,7 +11,7 @@ #include "system/hardware/hw.h" int main(int argc, char *argv[]) { - Hardware::config_cpu_rendering(); + Hardware::config_cpu_rendering(true); qInstallMessageHandler(swagLogMessageHandler); setpriority(PRIO_PROCESS, 0, -20); diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc index 543515c631..d52ee162bd 100644 --- a/selfdrive/navd/map_renderer.cc +++ b/selfdrive/navd/map_renderer.cc @@ -28,16 +28,16 @@ float get_zoom_level_for_scale(float lat, float meters_per_pixel) { return log2(num_tiles) - 1; } -QMapbox::Coordinate get_point_along_line(float lat, float lon, float bearing, float dist) { +QMapLibre::Coordinate get_point_along_line(float lat, float lon, float bearing, float dist) { float ang_dist = dist / EARTH_RADIUS_METERS; float lat1 = DEG2RAD(lat), lon1 = DEG2RAD(lon), bearing1 = DEG2RAD(bearing); float lat2 = asin(sin(lat1)*cos(ang_dist) + cos(lat1)*sin(ang_dist)*cos(bearing1)); float lon2 = lon1 + atan2(sin(bearing1)*sin(ang_dist)*cos(lat1), cos(ang_dist)-sin(lat1)*sin(lat2)); - return QMapbox::Coordinate(RAD2DEG(lat2), RAD2DEG(lon2)); + return QMapLibre::Coordinate(RAD2DEG(lat2), RAD2DEG(lon2)); } -MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_settings(settings) { +MapRenderer::MapRenderer(const QMapLibre::Settings &settings, bool online) : m_settings(settings) { QSurfaceFormat fmt; fmt.setRenderableType(QSurfaceFormat::OpenGLES); @@ -60,8 +60,8 @@ MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_set fbo.reset(new QOpenGLFramebufferObject(WIDTH, HEIGHT, fbo_format)); std::string style = util::read_file(STYLE_PATH); - m_map.reset(new QMapboxGL(nullptr, m_settings, fbo->size(), 1)); - m_map->setCoordinateZoom(QMapbox::Coordinate(0, 0), DEFAULT_ZOOM); + m_map.reset(new QMapLibre::Map(nullptr, m_settings, fbo->size(), 1)); + m_map->setCoordinateZoom(QMapLibre::Coordinate(0, 0), DEFAULT_ZOOM); m_map->setStyleJson(style.c_str()); m_map->createRenderer(); ever_loaded = false; @@ -70,20 +70,20 @@ MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_set m_map->setFramebufferObject(fbo->handle(), fbo->size()); gl_functions->glViewport(0, 0, WIDTH, HEIGHT); - QObject::connect(m_map.data(), &QMapboxGL::mapChanged, [=](QMapboxGL::MapChange change) { + QObject::connect(m_map.data(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { // Ignore expected signals // https://github.com/mapbox/mapbox-gl-native/blob/cf734a2fec960025350d8de0d01ad38aeae155a0/platform/qt/include/qmapboxgl.hpp#L116 if (ever_loaded) { - if (change != QMapboxGL::MapChange::MapChangeRegionWillChange && - change != QMapboxGL::MapChange::MapChangeRegionDidChange && - change != QMapboxGL::MapChange::MapChangeWillStartRenderingFrame && - change != QMapboxGL::MapChange::MapChangeDidFinishRenderingFrameFullyRendered) { + if (change != QMapLibre::Map::MapChange::MapChangeRegionWillChange && + change != QMapLibre::Map::MapChange::MapChangeRegionDidChange && + change != QMapLibre::Map::MapChange::MapChangeWillStartRenderingFrame && + change != QMapLibre::Map::MapChange::MapChangeDidFinishRenderingFrameFullyRendered) { LOGD("New map state: %d", change); } } }); - QObject::connect(m_map.data(), &QMapboxGL::mapLoadingFailed, [=](QMapboxGL::MapLoadingFailure err_code, const QString &reason) { + QObject::connect(m_map.data(), &QMapLibre::Map::mapLoadingFailed, [=](QMapLibre::Map::MapLoadingFailure err_code, const QString &reason) { LOGE("Map loading failed with %d: '%s'\n", err_code, reason.toStdString().c_str()); }); @@ -145,7 +145,7 @@ void MapRenderer::msgUpdate() { timer->start(0); } -void MapRenderer::updatePosition(QMapbox::Coordinate position, float bearing) { +void MapRenderer::updatePosition(QMapLibre::Coordinate position, float bearing) { if (m_map.isNull()) { return; } @@ -261,10 +261,10 @@ void MapRenderer::updateRoute(QList coordinates) { initLayers(); auto route_points = coordinate_list_to_collection(coordinates); - QMapbox::Feature feature(QMapbox::Feature::LineStringType, route_points, {}, {}); + QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); QVariantMap navSource; navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); + navSource["data"] = QVariant::fromValue(feature); m_map->updateSource("navSource", navSource); m_map->setLayoutProperty("navLayer", "visibility", "visible"); } @@ -273,10 +273,9 @@ void MapRenderer::initLayers() { if (!m_map->layerExists("navLayer")) { LOGD("Initializing navLayer"); QVariantMap nav; - nav["id"] = "navLayer"; nav["type"] = "line"; nav["source"] = "navSource"; - m_map->addLayer(nav, "road-intersection"); + m_map->addLayer("navLayer", nav, "road-intersection"); m_map->setPaintProperty("navLayer", "line-color", QColor("grey")); m_map->setPaintProperty("navLayer", "line-width", 5); m_map->setLayoutProperty("navLayer", "line-cap", "round"); @@ -296,9 +295,10 @@ extern "C" { QApplication *app = new QApplication(argc, argv); assert(app); - QMapboxGLSettings settings; + QMapLibre::Settings settings; + settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); settings.setApiBaseUrl(maps_host == nullptr ? MAPS_HOST : maps_host); - settings.setAccessToken(token == nullptr ? get_mapbox_token() : token); + settings.setApiKey(token == nullptr ? get_mapbox_token() : token); return new MapRenderer(settings, false); } diff --git a/selfdrive/navd/map_renderer.h b/selfdrive/navd/map_renderer.h index dc92c70b0f..fd5922b668 100644 --- a/selfdrive/navd/map_renderer.h +++ b/selfdrive/navd/map_renderer.h @@ -3,7 +3,8 @@ #include #include -#include +#include +#include #include #include #include @@ -19,7 +20,7 @@ class MapRenderer : public QObject { Q_OBJECT public: - MapRenderer(const QMapboxGLSettings &, bool online=true); + MapRenderer(const QMapLibre::Settings &, bool online=true); uint8_t* getImage(); void update(); bool loaded(); @@ -37,8 +38,8 @@ private: void publish(const double render_time, const bool loaded); void sendThumbnail(const uint64_t ts, const kj::Array &buf); - QMapboxGLSettings m_settings; - QScopedPointer m_map; + QMapLibre::Settings m_settings; + QScopedPointer m_map; void initLayers(); @@ -52,7 +53,7 @@ private: bool ever_loaded = false; public slots: - void updatePosition(QMapbox::Coordinate position, float bearing); + void updatePosition(QMapLibre::Coordinate position, float bearing); void updateRoute(QList coordinates); void msgUpdate(); }; diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index da2b8c06b9..2be703cdb2 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -15,7 +15,7 @@ from openpilot.selfdrive.navd.helpers import (Coordinate, coordinate_from_param, distance_along_geometry, maxspeed_to_ms, minimum_distance, parse_banner_instructions) -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog REROUTE_DISTANCE = 25 MANEUVER_TRANSITION_THRESHOLD = 10 @@ -71,8 +71,11 @@ class RouteEngine: self.ui_pid = ui_pid[0] self.update_location() - self.recompute_route() - self.send_instruction() + try: + self.recompute_route() + self.send_instruction() + except Exception: + cloudlog.exception("navd.failed_to_compute") def update_location(self): location = self.sm['liveLocationKalman'] @@ -196,7 +199,7 @@ class RouteEngine: self.send_route() def send_instruction(self): - msg = messaging.new_message('navInstruction') + msg = messaging.new_message('navInstruction', valid=True) if self.step_idx is None: msg.valid = False @@ -256,7 +259,10 @@ class RouteEngine: for i in range(self.step_idx + 1, len(self.route)): total_distance += self.route[i]['distance'] total_time += self.route[i]['duration'] - total_time_typical += self.route[i]['duration_typical'] + if self.route[i]['duration_typical'] is None: + total_time_typical += self.route[i]['duration'] + else: + total_time_typical += self.route[i]['duration_typical'] msg.navInstruction.distanceRemaining = total_distance msg.navInstruction.timeRemaining = total_time @@ -302,7 +308,7 @@ class RouteEngine: for path in self.route_geometry: coords += [c.as_dict() for c in path] - msg = messaging.new_message('navRoute') + msg = messaging.new_message('navRoute', valid=True) msg.navRoute.coordinates = coords self.pm.send('navRoute', msg) diff --git a/selfdrive/navd/tests/test_map_renderer.py b/selfdrive/navd/tests/test_map_renderer.py index dbd6add995..b5f186dbb0 100755 --- a/selfdrive/navd/tests/test_map_renderer.py +++ b/selfdrive/navd/tests/test_map_renderer.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import time import numpy as np import os import pytest @@ -10,26 +11,16 @@ import cereal.messaging as messaging from typing import Any from cereal.visionipc import VisionIpcClient, VisionStreamType -from openpilot.selfdrive.manager.process_config import managed_processes +from openpilot.common.mock.generators import LLK_DECIMATION, LOCATION1, LOCATION2, generate_liveLocationKalman +from openpilot.selfdrive.test.helpers import with_processes -LLK_DECIMATION = 10 CACHE_PATH = "/data/mbgl-cache-navd.db" -LOCATION1 = (32.7174, -117.16277) -LOCATION2 = (32.7558, -117.2037) - -DEFAULT_ITERATIONS = 30 * LLK_DECIMATION - +RENDER_FRAMES = 15 +DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION LOCATION1_REPEATED = [LOCATION1] * DEFAULT_ITERATIONS LOCATION2_REPEATED = [LOCATION2] * DEFAULT_ITERATIONS -def gen_llk(location=LOCATION1): - msg = messaging.new_message('liveLocationKalman') - msg.liveLocationKalman.positionGeodetic = {'value': [*location, 0], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.calibratedOrientationNED = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.status = 'valid' - return msg - class MapBoxInternetDisabledRequestHandler(http.server.BaseHTTPRequestHandler): INTERNET_ACTIVE = True @@ -60,7 +51,8 @@ class MapBoxInternetDisabledRequestHandler(http.server.BaseHTTPRequestHandler): class MapBoxInternetDisabledServer(threading.Thread): def run(self): - self.server = http.server.HTTPServer(("127.0.0.1", 5000), MapBoxInternetDisabledRequestHandler) + self.server = http.server.HTTPServer(("127.0.0.1", 0), MapBoxInternetDisabledRequestHandler) + self.port = self.server.server_port self.server.serve_forever() def stop(self): @@ -74,13 +66,15 @@ class MapBoxInternetDisabledServer(threading.Thread): class TestMapRenderer(unittest.TestCase): - server = MapBoxInternetDisabledServer() + server: MapBoxInternetDisabledServer @classmethod def setUpClass(cls): assert "MAPBOX_TOKEN" in os.environ cls.original_token = os.environ["MAPBOX_TOKEN"] + cls.server = MapBoxInternetDisabledServer() cls.server.start() + time.sleep(0.5) # wait for server to startup @classmethod def tearDownClass(cls) -> None: @@ -88,7 +82,7 @@ class TestMapRenderer(unittest.TestCase): def setUp(self): self.server.enable_internet() - os.environ['MAPS_HOST'] = 'http://localhost:5000' + os.environ['MAPS_HOST'] = f'http://localhost:{self.server.port}' self.sm = messaging.SubMaster(['mapRenderState']) self.pm = messaging.PubMaster(['liveLocationKalman']) @@ -97,15 +91,11 @@ class TestMapRenderer(unittest.TestCase): if os.path.exists(CACHE_PATH): os.remove(CACHE_PATH) - def tearDown(self): - managed_processes['mapsd'].stop() - def _setup_test(self): - # start + sync up - managed_processes['mapsd'].start() - assert self.pm.wait_for_readers_to_update("liveLocationKalman", 10) + time.sleep(0.5) + assert VisionIpcClient.available_streams("navd", False) == {VisionStreamType.VISION_STREAM_MAP, } assert self.vipc.connect(False) self.vipc.recv() @@ -130,7 +120,7 @@ class TestMapRenderer(unittest.TestCase): if starting_frame_id is None: starting_frame_id = prev_frame_id - llk = gen_llk(location) + llk = generate_liveLocationKalman(location) self.pm.send("liveLocationKalman", llk) self.pm.wait_for_readers_to_update("liveLocationKalman", 10) self.sm.update(1000 if frame_expected else 0) @@ -164,17 +154,23 @@ class TestMapRenderer(unittest.TestCase): assert self.vipc.timestamp_sof == llk.logMonoTime assert self.vipc.frame_id == self.sm['mapRenderState'].frameId + assert frames_since_test_start >= RENDER_FRAMES + return render_times + @with_processes(["mapsd"]) def test_with_internet(self): self._setup_test() self._run_test(True) + @with_processes(["mapsd"]) def test_with_no_internet(self): self.server.disable_internet() self._setup_test() self._run_test(False) + @with_processes(["mapsd"]) + @pytest.mark.skip(reason="slow, flaky, and unlikely to break") def test_recover_from_no_internet(self): self._setup_test() self._run_test(True) @@ -187,8 +183,7 @@ class TestMapRenderer(unittest.TestCase): self.server.enable_internet() self._run_test(True, LOCATION2_REPEATED) - self._run_test(True, LOCATION2_REPEATED) - + @with_processes(["mapsd"]) @pytest.mark.tici def test_render_time_distribution(self): self._setup_test() diff --git a/selfdrive/navd/tests/test_navd.py b/selfdrive/navd/tests/test_navd.py new file mode 100755 index 0000000000..61be6cc387 --- /dev/null +++ b/selfdrive/navd/tests/test_navd.py @@ -0,0 +1,63 @@ +#!/usr/bin/env python3 +import json +import random +import unittest +import numpy as np + +from parameterized import parameterized + +import cereal.messaging as messaging +from openpilot.common.params import Params +from openpilot.selfdrive.manager.process_config import managed_processes + + +class TestNavd(unittest.TestCase): + def setUp(self): + self.params = Params() + self.sm = messaging.SubMaster(['navRoute', 'navInstruction']) + + def tearDown(self): + managed_processes['navd'].stop() + + def _check_route(self, start, end, check_coords=True): + self.params.put("NavDestination", json.dumps(end)) + self.params.put("LastGPSPosition", json.dumps(start)) + + managed_processes['navd'].start() + for _ in range(30): + self.sm.update(1000) + if all(f > 0 for f in self.sm.recv_frame.values()): + break + else: + raise Exception("didn't get a route") + + assert managed_processes['navd'].proc.is_alive() + managed_processes['navd'].stop() + + # ensure start and end match up + if check_coords: + coords = self.sm['navRoute'].coordinates + assert np.allclose([start['latitude'], start['longitude'], end['latitude'], end['longitude']], + [coords[0].latitude, coords[0].longitude, coords[-1].latitude, coords[-1].longitude], + rtol=1e-3) + + def test_simple(self): + start = { + "latitude": 32.7427228, + "longitude": -117.2321177, + } + end = { + "latitude": 32.7557004, + "longitude": -117.268002, + } + self._check_route(start, end) + + @parameterized.expand([(i,) for i in range(10)]) + def test_random(self, index): + start = {"latitude": random.uniform(-90, 90), "longitude": random.uniform(-180, 180)} + end = {"latitude": random.uniform(-90, 90), "longitude": random.uniform(-180, 180)} + self._check_route(start, end, check_coords=False) + + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/sentry.py b/selfdrive/sentry.py index b8bc8eff12..5b63a9fe2d 100644 --- a/selfdrive/sentry.py +++ b/selfdrive/sentry.py @@ -6,7 +6,7 @@ from sentry_sdk.integrations.threading import ThreadingIntegration from openpilot.common.params import Params from openpilot.selfdrive.athena.registration import is_registered_device from openpilot.system.hardware import HARDWARE, PC -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.system.version import get_branch, get_commit, get_origin, get_version, \ is_comma_remote, is_dirty, is_tested_branch @@ -44,7 +44,7 @@ def set_tag(key: str, value: str) -> None: def init(project: SentryProject) -> bool: # forks like to mess with this, so double check - comma_remote = is_comma_remote() and "commaai" in get_origin(default="") + comma_remote = is_comma_remote() and "commaai" in get_origin() if not comma_remote or not is_registered_device() or PC: return False @@ -54,14 +54,13 @@ def init(project: SentryProject) -> bool: integrations = [] if project == SentryProject.SELFDRIVE: integrations.append(ThreadingIntegration(propagate_hub=True)) - else: - sentry_sdk.utils.MAX_STRING_LENGTH = 8192 sentry_sdk.init(project.value, default_integrations=False, release=get_version(), integrations=integrations, traces_sample_rate=1.0, + max_value_length=8192, environment=env) sentry_sdk.set_user({"id": dongle_id}) diff --git a/selfdrive/statsd.py b/selfdrive/statsd.py index 8acf406515..94572b82c7 100755 --- a/selfdrive/statsd.py +++ b/selfdrive/statsd.py @@ -9,11 +9,12 @@ from typing import NoReturn, Union, List, Dict from openpilot.common.params import Params from cereal.messaging import SubMaster -from openpilot.system.swaglog import cloudlog +from openpilot.system.hardware.hw import Paths +from openpilot.common.swaglog import cloudlog from openpilot.system.hardware import HARDWARE from openpilot.common.file_helpers import atomic_write_in_dir from openpilot.system.version import get_normalized_origin, get_short_branch, get_short_version, is_dirty -from openpilot.system.loggerd.config import STATS_DIR, STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S +from openpilot.system.loggerd.config import STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S class METRIC_TYPE: @@ -80,6 +81,8 @@ def main() -> NoReturn: sock = ctx.socket(zmq.PULL) sock.bind(STATS_SOCKET) + STATS_DIR = Paths.stats_root() + # initialize stats directory Path(STATS_DIR).mkdir(parents=True, exist_ok=True) diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 552070f024..0e7912a989 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -11,8 +11,6 @@ from openpilot.system.version import training_version, terms_version def set_params_enabled(): - os.environ['PASSIVE'] = "0" - os.environ['REPLAY'] = "1" os.environ['FINGERPRINT'] = "TOYOTA COROLLA TSS2 2019" os.environ['LOGPRINT'] = "debug" @@ -20,7 +18,6 @@ def set_params_enabled(): params.put("HasAcceptedTerms", terms_version) params.put("CompletedTrainingVersion", training_version) params.put_bool("OpenpilotEnabledToggle", True) - params.put_bool("Passive", False) # valid calib msg = messaging.new_message('liveCalibration') @@ -71,4 +68,11 @@ def with_processes(processes, init_time=0, ignore_stopped=None): def noop(*args, **kwargs): - pass \ No newline at end of file + pass + + +def read_segment_list(segment_list_path): + with open(segment_list_path, "r") as f: + seg_list = f.read().splitlines() + + return [(platform[2:], segment) for platform, segment in zip(seg_list[::2], seg_list[1::2], strict=True)] diff --git a/selfdrive/test/pytest-tici.ini b/selfdrive/test/pytest-tici.ini deleted file mode 100644 index a553018309..0000000000 --- a/selfdrive/test/pytest-tici.ini +++ /dev/null @@ -1,5 +0,0 @@ -[pytest] -addopts = -Werror --strict-config --strict-markers -markers = - slow: tests that take awhile to run and can be skipped with -m 'not slow' - tici: tests that are only meant to run on the C3/C3X diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index c34e097f73..5c85312f1a 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -29,7 +29,6 @@ sudo abctl --set_success # patch sshd config sudo mount -o rw,remount / -echo tici-$(cat /proc/cmdline | sed -e 's/^.*androidboot.serialno=//' -e 's/ .*$//') | sudo tee /etc/hostname sudo sed -i "s,/data/params/d/GithubSshKeys,/usr/comma/setup_keys," /etc/ssh/sshd_config sudo systemctl daemon-reload sudo systemctl restart ssh @@ -80,9 +79,7 @@ safe_checkout() { echo "git checkout done, t=$SECONDS" du -hs $SOURCE_DIR $SOURCE_DIR/.git - if [ -z "SKIP_COPY" ]; then - rsync -a --delete $SOURCE_DIR $TEST_DIR - fi + rsync -a --delete $SOURCE_DIR $TEST_DIR } unsafe_checkout() { diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 0e9d207da3..de8a4420b3 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -29,35 +29,35 @@ from openpilot.tools.lib.logreader import LogReader # Baseline CPU usage by process PROCS = { - "selfdrive.controls.controlsd": 39.0, + "selfdrive.controls.controlsd": 41.0, "./loggerd": 14.0, "./encoderd": 17.0, "./camerad": 14.5, "./locationd": 11.0, - "./mapsd": 1.5, - "selfdrive.controls.plannerd": 16.5, - "./_ui": 18.0, + "./mapsd": (0.5, 10.0), + "selfdrive.controls.plannerd": 11.0, + "./ui": 18.0, "selfdrive.locationd.paramsd": 9.0, "./sensord": 7.0, - "selfdrive.controls.radard": 4.5, + "selfdrive.controls.radard": 7.0, "selfdrive.modeld.modeld": 13.0, "selfdrive.modeld.dmonitoringmodeld": 8.0, "selfdrive.modeld.navmodeld": 1.0, "selfdrive.thermald.thermald": 3.87, "selfdrive.locationd.calibrationd": 2.0, "selfdrive.locationd.torqued": 5.0, - "./_soundd": (1.0, 65.0), + "selfdrive.ui.soundd": 3.5, "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 1.54, "system.logmessaged": 0.2, "selfdrive.tombstoned": 0, "./logcatd": 0, - "system.micd": 10.0, - "system.timezoned": 0, + "system.micd": 6.0, + "system.timed": 0, "selfdrive.boardd.pandad": 0, "selfdrive.statsd": 0.4, "selfdrive.navd.navd": 0.4, - "system.loggerd.uploader": 3.0, + "system.loggerd.uploader": (0.5, 15.0), "system.loggerd.deleter": 0.1, } @@ -69,7 +69,7 @@ PROCS.update({ }, "tizi": { "./boardd": 19.0, - "system.sensord.rawgps.rawgpsd": 1.0, + "system.qcomgpsd.qcomgpsd": 1.0, } }.get(HARDWARE.get_device_type(), {})) @@ -82,7 +82,6 @@ TIMINGS = { "carState": [2.5, 0.35], "carControl": [2.5, 0.35], "controlsState": [2.5, 0.35], - "lateralPlan": [2.5, 0.5], "longitudinalPlan": [2.5, 0.5], "roadCameraState": [2.5, 0.35], "driverCameraState": [2.5, 0.35], @@ -113,17 +112,12 @@ class TestOnroad(unittest.TestCase): # setup env params = Params() - if "CI" in os.environ: - params.clear_all() params.remove("CurrentRoute") set_params_enabled() + os.environ['REPLAY'] = '1' os.environ['TESTING_CLOSET'] = '1' if os.path.exists(Paths.log_root()): shutil.rmtree(Paths.log_root()) - os.system("rm /dev/shm/*") - - # Make sure athena isn't running - os.system("pkill -9 -f athena") # start manager and run openpilot for a minute proc = None @@ -133,7 +127,7 @@ class TestOnroad(unittest.TestCase): sm = messaging.SubMaster(['carState']) with Timeout(150, "controls didn't start"): - while sm.rcv_frame['carState'] < 0: + while sm.recv_frame['carState'] < 0: sm.update(1000) # make sure we get at least two full segments @@ -168,6 +162,15 @@ class TestOnroad(unittest.TestCase): cls.lr = list(LogReader(os.path.join(str(cls.segments[1]), "rlog"))) cls.log_path = cls.segments[1] + cls.log_sizes = {} + for f in cls.log_path.iterdir(): + assert f.is_file() + cls.log_sizes[f] = f.stat().st_size / 1e6 + if f.name in ("qlog", "rlog"): + with open(f, 'rb') as ff: + cls.log_sizes[f] = len(bz2.compress(ff.read())) / 1e6 + + @cached_property def service_msgs(self): msgs = defaultdict(list) @@ -198,14 +201,7 @@ class TestOnroad(unittest.TestCase): self.assertEqual(len(big_logs), 0, f"Log spam: {big_logs}") def test_log_sizes(self): - for f in self.log_path.iterdir(): - assert f.is_file() - - sz = f.stat().st_size / 1e6 - if f.name in ("qlog", "rlog"): - with open(f, 'rb') as ff: - sz = len(bz2.compress(ff.read())) / 1e6 - + for f, sz in self.log_sizes.items(): if f.name == "qcamera.ts": assert 2.15 < sz < 2.35 elif f.name == "qlog": @@ -303,7 +299,7 @@ class TestOnroad(unittest.TestCase): self.assertLessEqual(max(mems) - min(mems), 3.0) def test_gpu_usage(self): - self.assertEqual(self.gpu_procs, {"weston", "_ui", "camerad", "selfdrive.modeld.modeld"}) + self.assertEqual(self.gpu_procs, {"weston", "ui", "camerad", "selfdrive.modeld.modeld"}) def test_camera_processing_time(self): result = "\n" @@ -342,7 +338,7 @@ class TestOnroad(unittest.TestCase): result += "----------------- MPC Timing ------------------\n" result += "------------------------------------------------\n" - cfgs = [("lateralPlan", 0.05, 0.05), ("longitudinalPlan", 0.05, 0.05)] + cfgs = [("longitudinalPlan", 0.05, 0.05),] for (s, instant_max, avg_max) in cfgs: ts = [getattr(m, s).solverExecutionTime for m in self.service_msgs[s]] self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}") @@ -408,7 +404,7 @@ class TestOnroad(unittest.TestCase): def test_startup(self): startup_alert = None for msg in self.lrs[0]: - # can't use carEvents because the first msg can be dropped while loggerd is starting up + # can't use onroadEvents because the first msg can be dropped while loggerd is starting up if msg.which() == "controlsState": startup_alert = msg.controlsState.alertText1 break @@ -417,8 +413,8 @@ class TestOnroad(unittest.TestCase): def test_engagable(self): no_entries = Counter() - for m in self.service_msgs['carEvents']: - for evt in m.carEvents: + for m in self.service_msgs['onroadEvents']: + for evt in m.onroadEvents: if evt.noEntry: no_entries[evt.name] += 1 @@ -428,4 +424,4 @@ class TestOnroad(unittest.TestCase): if __name__ == "__main__": - unittest.main() + pytest.main() diff --git a/selfdrive/test/test_time_to_onroad.py b/selfdrive/test/test_time_to_onroad.py index cc2cc6514e..a3f803e221 100755 --- a/selfdrive/test/test_time_to_onroad.py +++ b/selfdrive/test/test_time_to_onroad.py @@ -18,30 +18,40 @@ def test_time_to_onroad(): proc = subprocess.Popen(["python", manager_path]) start_time = time.monotonic() - sm = messaging.SubMaster(['controlsState', 'deviceState', 'carEvents']) + sm = messaging.SubMaster(['controlsState', 'deviceState', 'onroadEvents', 'sendcan']) try: - # wait for onroad - with Timeout(20, "timed out waiting to go onroad"): - while True: - sm.update(1000) - if sm['deviceState'].started: - break - time.sleep(1) + # wait for onroad. timeout assumes panda is up to date + with Timeout(10, "timed out waiting to go onroad"): + while not sm['deviceState'].started: + sm.update(100) # wait for engageability - with Timeout(10, "timed out waiting for engageable"): - while True: - sm.update(1000) - if sm['controlsState'].engageable: - break - time.sleep(1) + try: + with Timeout(10, "timed out waiting for engageable"): + sendcan_frame = None + while True: + sm.update(100) + + # sendcan is only sent once we're initialized + if sm.seen['controlsState'] and sendcan_frame is None: + sendcan_frame = sm.frame + + if sendcan_frame is not None and sm.recv_frame['sendcan'] > sendcan_frame: + sm.update(100) + assert sm['controlsState'].engageable, f"events: {sm['onroadEvents']}" + break + finally: + print(f"onroad events: {sm['onroadEvents']}") print(f"engageable after {time.monotonic() - start_time:.2f}s") - # once we're enageable, must be for the next few seconds - for _ in range(500): + # once we're enageable, must stay for the next few seconds + st = time.monotonic() + while (time.monotonic() - st) < 10.: sm.update(100) - assert sm['controlsState'].engageable, f"events: {sm['carEvents']}" + assert sm.all_alive(), sm.alive + assert sm['controlsState'].engageable, f"events: {sm['onroadEvents']}" + assert sm['controlsState'].cumLagMs < 10. finally: proc.terminate() - if proc.wait(60) is None: + if proc.wait(20) is None: proc.kill() diff --git a/selfdrive/thermald/fan_controller.py b/selfdrive/thermald/fan_controller.py index 64cd4c78ee..19c3292ce2 100755 --- a/selfdrive/thermald/fan_controller.py +++ b/selfdrive/thermald/fan_controller.py @@ -3,7 +3,7 @@ from abc import ABC, abstractmethod from openpilot.common.realtime import DT_TRML from openpilot.common.numpy_fast import interp -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.controls.lib.pid import PIDController class BaseFanController(ABC): diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 0b3c73a1c0..f74118b568 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -2,9 +2,9 @@ import time import threading from typing import Optional -from openpilot.common.params import Params, put_nonblocking +from openpilot.common.params import Params from openpilot.system.hardware import HARDWARE -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.statsd import statlog CAR_VOLTAGE_LOW_PASS_K = 0.011 # LPF gain for 45s tau (dt/tau / (dt/tau + 1)) @@ -14,7 +14,6 @@ CAR_BATTERY_CAPACITY_uWh = 30e6 CAR_CHARGING_RATE_W = 45 VBATT_PAUSE_CHARGING = 11.8 # Lower limit on the LPF car battery voltage -VBATT_INSTANT_PAUSE_CHARGING = 7.0 # Lower limit on the instant car battery voltage measurements to avoid triggering on instant power loss MAX_TIME_OFFROAD_S = 30*3600 MIN_ON_TIME_S = 3600 DELAY_SHUTDOWN_TIME_S = 300 # Wait at least DELAY_SHUTDOWN_TIME_S seconds after offroad_time to shutdown. @@ -60,7 +59,7 @@ class PowerMonitoring: self.car_battery_capacity_uWh = max(self.car_battery_capacity_uWh, 0) self.car_battery_capacity_uWh = min(self.car_battery_capacity_uWh, CAR_BATTERY_CAPACITY_uWh) if now - self.last_save_time >= 10: - put_nonblocking("CarBatteryCapacity", str(int(self.car_battery_capacity_uWh))) + self.params.put_nonblocking("CarBatteryCapacity", str(int(self.car_battery_capacity_uWh))) self.last_save_time = now # First measurement, set integration time @@ -117,7 +116,6 @@ class PowerMonitoring: should_shutdown = False offroad_time = (now - offroad_timestamp) low_voltage_shutdown = (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3) and - self.car_voltage_instant_mV > (VBATT_INSTANT_PAUSE_CHARGING * 1e3) and offroad_time > VOLTAGE_SHUTDOWN_MIN_OFFROAD_TIME_S) should_shutdown |= offroad_time > MAX_TIME_OFFROAD_S should_shutdown |= low_voltage_shutdown diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 3ccb9349e1..e868f2ffdd 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import datetime import os import json import queue @@ -15,7 +14,6 @@ import cereal.messaging as messaging from cereal import log from cereal.services import SERVICE_LIST from openpilot.common.dict_helpers import strip_deprecated_keys -from openpilot.common.time import MIN_DATE from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.params import Params from openpilot.common.realtime import DT_TRML @@ -23,7 +21,7 @@ from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, TICI, AGNOS from openpilot.system.loggerd.config import get_available_percent from openpilot.selfdrive.statsd import statlog -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.thermald.power_monitoring import PowerMonitoring from openpilot.selfdrive.thermald.fan_controller import TiciFanController from openpilot.system.version import terms_version, training_version @@ -81,11 +79,10 @@ def read_tz(x): def read_thermal(thermal_config): - dat = messaging.new_message('deviceState') + dat = messaging.new_message('deviceState', valid=True) dat.deviceState.cpuTempC = [read_tz(z) / thermal_config.cpu[1] for z in thermal_config.cpu[0]] dat.deviceState.gpuTempC = [read_tz(z) / thermal_config.gpu[1] for z in thermal_config.gpu[0]] dat.deviceState.memoryTempC = read_tz(thermal_config.mem[0]) / thermal_config.mem[1] - dat.deviceState.ambientTempC = read_tz(thermal_config.ambient[0]) / thermal_config.ambient[1] dat.deviceState.pmicTempC = [read_tz(z) / thermal_config.pmic[1] for z in thermal_config.pmic[0]] return dat @@ -168,7 +165,7 @@ def hw_state_thread(end_event, hw_queue): def thermald_thread(end_event, hw_queue) -> None: pm = messaging.PubMaster(['deviceState']) - sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "controlsState", "pandaStates"], poll=["pandaStates"]) + sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "controlsState", "pandaStates"], poll="pandaStates") count = 0 @@ -235,7 +232,7 @@ def thermald_thread(end_event, hw_queue) -> None: if TICI: fan_controller = TiciFanController() - elif (time.monotonic() - sm.rcv_time['pandaStates']) > DISCONNECT_TIMEOUT: + elif (time.monotonic() - sm.recv_time['pandaStates']) > DISCONNECT_TIMEOUT: if onroad_conditions["ignition"]: onroad_conditions["ignition"] = False cloudlog.error("panda timed out onroad") @@ -247,8 +244,10 @@ def thermald_thread(end_event, hw_queue) -> None: msg.deviceState.freeSpacePercent = get_available_percent(default=100.0) msg.deviceState.memoryUsagePercent = int(round(psutil.virtual_memory().percent)) - msg.deviceState.cpuUsagePercent = [int(round(n)) for n in psutil.cpu_percent(percpu=True)] msg.deviceState.gpuUsagePercent = int(round(HARDWARE.get_gpu_usage_percent())) + online_cpu_usage = [int(round(n)) for n in psutil.cpu_percent(percpu=True)] + offline_cpu_usage = [0., ] * (len(msg.deviceState.cpuTempC) - len(online_cpu_usage)) + msg.deviceState.cpuUsagePercent = online_cpu_usage + offline_cpu_usage msg.deviceState.networkType = last_hw_state.network_type msg.deviceState.networkMetered = last_hw_state.network_metered @@ -293,25 +292,22 @@ def thermald_thread(end_event, hw_queue) -> None: # **** starting logic **** - # Ensure date/time are valid - now = datetime.datetime.utcnow() - startup_conditions["time_valid"] = now > MIN_DATE - set_offroad_alert_if_changed("Offroad_InvalidTime", (not startup_conditions["time_valid"]) and peripheral_panda_present) - startup_conditions["up_to_date"] = params.get("Offroad_ConnectivityNeeded") is None or params.get_bool("DisableUpdates") or params.get_bool("SnoozeUpdate") startup_conditions["not_uninstalling"] = not params.get_bool("DoUninstall") startup_conditions["accepted_terms"] = params.get("HasAcceptedTerms") == terms_version # with 2% left, we killall, otherwise the phone will take a long time to boot startup_conditions["free_space"] = msg.deviceState.freeSpacePercent > 2 - startup_conditions["completed_training"] = params.get("CompletedTrainingVersion") == training_version or \ - params.get_bool("Passive") + startup_conditions["completed_training"] = params.get("CompletedTrainingVersion") == training_version startup_conditions["not_driver_view"] = not params.get_bool("IsDriverViewEnabled") startup_conditions["not_taking_snapshot"] = not params.get_bool("IsTakingSnapshot") # must be at an engageable thermal band to go onroad startup_conditions["device_temp_engageable"] = thermal_status < ThermalStatus.red + # ensure device is fully booted + startup_conditions["device_booted"] = startup_conditions.get("device_booted", False) or HARDWARE.booted() + # if the temperature enters the danger zone, go offroad to cool down onroad_conditions["device_temp_good"] = thermal_status < ThermalStatus.danger extra_text = f"{offroad_comp_temp:.1f}C" @@ -415,7 +411,6 @@ def thermald_thread(end_event, hw_queue) -> None: for i, temp in enumerate(msg.deviceState.gpuTempC): statlog.gauge(f"gpu{i}_temperature", temp) statlog.gauge("memory_temperature", msg.deviceState.memoryTempC) - statlog.gauge("ambient_temperature", msg.deviceState.ambientTempC) for i, temp in enumerate(msg.deviceState.pmicTempC): statlog.gauge(f"pmic{i}_temperature", temp) for i, temp in enumerate(last_hw_state.nvme_temps): @@ -444,6 +439,8 @@ def thermald_thread(end_event, hw_queue) -> None: except Exception: cloudlog.exception("failed to save offroad status") + params.put_bool_nonblocking("NetworkMetered", msg.deviceState.networkMetered) + count += 1 should_start_prev = should_start diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index 3f2fb28d23..ba3582d130 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -9,10 +9,9 @@ import time import glob from typing import NoReturn -from openpilot.common.file_helpers import mkdirs_exists_ok import openpilot.selfdrive.sentry as sentry from openpilot.system.hardware.hw import Paths -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.system.version import get_commit MAX_SIZE = 1_000_000 * 100 # allow up to 100M @@ -125,10 +124,10 @@ def report_tombstone_apport(fn): clean_path = path.replace('/', '_') date = datetime.datetime.now().strftime("%Y-%m-%d--%H-%M-%S") - new_fn = f"{date}_{get_commit(default='nocommit')[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN] + new_fn = f"{date}_{(get_commit() or 'nocommit')[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN] crashlog_dir = os.path.join(Paths.log_root(), "crash") - mkdirs_exists_ok(crashlog_dir) + os.makedirs(crashlog_dir, exist_ok=True) # Files could be on different filesystems, copy, then delete shutil.copy(fn, os.path.join(crashlog_dir, new_fn)) diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore index 8ad5d39493..f9724816da 100644 --- a/selfdrive/ui/.gitignore +++ b/selfdrive/ui/.gitignore @@ -3,10 +3,13 @@ moc_* translations/main_test_en.* +_text +_spinner + +ui +mui watch3 installer/installers/* -qt/text -qt/spinner qt/setup/setup qt/setup/reset qt/setup/wifi diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 916f1017a3..ea5734fe6e 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -11,14 +11,13 @@ if arch == 'larch64': maps = arch in ['larch64', 'aarch64', 'x86_64'] -if maps and arch != 'larch64': - rpath = [Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath] - qt_env["RPATH"] += rpath - if arch == "Darwin": del base_libs[base_libs.index('OpenCL')] qt_env['FRAMEWORKS'] += ['OpenCL'] +# FIXME: remove this once we're on 5.15 (24.04) +qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] + qt_util = qt_env.Library("qt_util", ["#selfdrive/ui/qt/api.cc", "#selfdrive/ui/qt/util.cc"], LIBS=base_libs) widgets_src = ["ui.cc", "qt/widgets/input.cc", "qt/widgets/wifi.cc", "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", @@ -28,7 +27,7 @@ widgets_src = ["ui.cc", "qt/widgets/input.cc", "qt/widgets/wifi.cc", qt_env['CPPDEFINES'] = [] if maps: - base_libs += ['qmapboxgl'] + base_libs += ['QMapLibre'] widgets_src += ["qt/maps/map_helpers.cc", "qt/maps/map_settings.cc", "qt/maps/map.cc", "qt/maps/map_panel.cc", "qt/maps/map_eta.cc", "qt/maps/map_instructions.cc"] qt_env['CPPDEFINES'] += ["ENABLE_MAPS"] @@ -70,20 +69,14 @@ qt_env.Command(assets, [assets_src, translations_assets_src], f"rcc $SOURCES -o qt_env.Depends(assets, Glob('#selfdrive/assets/*', exclude=[assets, assets_src, translations_assets_src, "#selfdrive/assets/assets.o"]) + [lrelease]) asset_obj = qt_env.Object("assets", assets) -# build soundd -qt_env.Program("soundd/_soundd", ["soundd/main.cc", "soundd/sound.cc"], LIBS=qt_libs) -if GetOption('extras'): - qt_env.Program("tests/playsound", "tests/playsound.cc", LIBS=base_libs) - qt_env.Program('tests/test_sound', ['tests/test_runner.cc', 'soundd/sound.cc', 'tests/test_sound.cc'], LIBS=qt_libs) - qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs) # spinner and text window -qt_env.Program("qt/text", ["qt/text.cc"], LIBS=qt_libs) -qt_env.Program("qt/spinner", ["qt/spinner.cc"], LIBS=qt_libs) +qt_env.Program("_text", ["qt/text.cc"], LIBS=qt_libs) +qt_env.Program("_spinner", ["qt/spinner.cc"], LIBS=qt_libs) # build main UI -qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs) +qt_env.Program("ui", qt_src + [asset_obj], LIBS=qt_libs) if GetOption('extras'): qt_src.remove("main.cc") # replaced by test_runner qt_env.Program('tests/test_translations', [asset_obj, 'tests/test_runner.cc', 'tests/test_translations.cc'] + qt_src, LIBS=qt_libs) @@ -99,28 +92,25 @@ if GetOption('extras') and arch != "Darwin": # build updater UI qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs) + # build mui + qt_env.Program("mui", ["mui.cc"], LIBS=qt_libs) + # build installers senv = qt_env.Clone() senv['LINKFLAGS'].append('-Wl,-strip-debug') release = "release3" - dashcam = "dashcam3" installers = [ ("openpilot", release), ("openpilot_test", f"{release}-staging"), ("openpilot_nightly", "nightly"), ("openpilot_internal", "master"), - ("dashcam", dashcam), - ("dashcam_test", f"{dashcam}-staging"), ] - cont = {} - for brand in ("openpilot", "dashcam"): - cont[brand] = senv.Command(f"installer/continue_{brand}.o", f"installer/continue_{brand}.sh", - "ld -r -b binary -o $TARGET $SOURCE") + cont = senv.Command(f"installer/continue_openpilot.o", f"installer/continue_openpilot.sh", + "ld -r -b binary -o $TARGET $SOURCE") for name, branch in installers: - brand = "dashcam" if "dashcam" in branch else "openpilot" - d = {'BRANCH': f"'\"{branch}\"'", 'BRAND': f"'\"{brand}\"'"} + d = {'BRANCH': f"'\"{branch}\"'"} if "internal" in name: d['INTERNAL'] = "1" @@ -129,9 +119,9 @@ if GetOption('extras') and arch != "Darwin": r.raise_for_status() d['SSH_KEYS'] = f'\\"{r.text.strip()}\\"' obj = senv.Object(f"installer/installers/installer_{name}.o", ["installer/installer.cc"], CPPDEFINES=d) - f = senv.Program(f"installer/installers/installer_{name}", [obj, cont[brand]], LIBS=qt_libs) + f = senv.Program(f"installer/installers/installer_{name}", [obj, cont], LIBS=qt_libs) # keep installers small - assert f[0].get_size() < 300*1e3 + assert f[0].get_size() < 350*1e3 # build watch3 if arch in ['x86_64', 'aarch64', 'Darwin'] or GetOption('extras'): diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index 179ce60c63..d43ed37ae8 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -33,8 +33,8 @@ const QString CACHE_PATH = "/data/openpilot.cache"; #define INSTALL_PATH "/data/openpilot" #define TMP_INSTALL_PATH "/data/tmppilot" -extern const uint8_t str_continue[] asm("_binary_selfdrive_ui_installer_continue_" BRAND "_sh_start"); -extern const uint8_t str_continue_end[] asm("_binary_selfdrive_ui_installer_continue_" BRAND "_sh_end"); +extern const uint8_t str_continue[] asm("_binary_selfdrive_ui_installer_continue_openpilot_sh_start"); +extern const uint8_t str_continue_end[] asm("_binary_selfdrive_ui_installer_continue_openpilot_sh_end"); bool time_valid() { time_t rawtime; diff --git a/selfdrive/ui/mui.cc b/selfdrive/ui/mui.cc new file mode 100644 index 0000000000..98029ee311 --- /dev/null +++ b/selfdrive/ui/mui.cc @@ -0,0 +1,50 @@ +#include +#include +#include + +#include "cereal/messaging/messaging.h" +#include "selfdrive/ui/ui.h" +#include "selfdrive/ui/qt/qt_window.h" + +int main(int argc, char *argv[]) { + QApplication a(argc, argv); + QWidget w; + setMainWindow(&w); + + w.setStyleSheet("background-color: black;"); + + // our beautiful UI + QVBoxLayout *layout = new QVBoxLayout(&w); + QLabel *label = new QLabel("〇"); + layout->addWidget(label, 0, Qt::AlignCenter); + + QTimer timer; + QObject::connect(&timer, &QTimer::timeout, [=]() { + static SubMaster sm({"deviceState", "controlsState"}); + + bool onroad_prev = sm.allAliveAndValid({"deviceState"}) && + sm["deviceState"].getDeviceState().getStarted(); + sm.update(0); + + bool onroad = sm.allAliveAndValid({"deviceState"}) && + sm["deviceState"].getDeviceState().getStarted(); + + if (onroad) { + label->setText("〇"); + auto cs = sm["controlsState"].getControlsState(); + UIStatus status = cs.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; + label->setStyleSheet(QString("color: %1; font-size: 250px;").arg(bg_colors[status].name())); + } else { + label->setText("offroad"); + label->setStyleSheet("color: grey; font-size: 40px;"); + } + + if ((onroad != onroad_prev) || sm.frame < 2) { + Hardware::set_brightness(50); + Hardware::set_display_power(onroad); + } + }); + timer.start(50); + + return a.exec(); +} diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index db56fcdcfc..a5644bae4f 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -18,7 +18,7 @@ const float MAX_PITCH = 50; const float MIN_PITCH = 0; const float MAP_SCALE = 2; -MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings), velocity_filter(0, 10, 0.05, false) { +MapWindow::MapWindow(const QMapLibre::Settings &settings) : m_settings(settings), velocity_filter(0, 10, 0.05, false) { QObject::connect(uiState(), &UIState::uiUpdate, this, &MapWindow::updateState); map_overlay = new QWidget (this); @@ -57,10 +57,10 @@ void MapWindow::initLayers() { if (!m_map->layerExists("modelPathLayer")) { qDebug() << "Initializing modelPathLayer"; QVariantMap modelPath; - modelPath["id"] = "modelPathLayer"; + //modelPath["id"] = "modelPathLayer"; modelPath["type"] = "line"; modelPath["source"] = "modelPathSource"; - m_map->addLayer(modelPath); + m_map->addLayer("modelPathLayer", modelPath); m_map->setPaintProperty("modelPathLayer", "line-color", QColor("red")); m_map->setPaintProperty("modelPathLayer", "line-width", 5.0); m_map->setLayoutProperty("modelPathLayer", "line-cap", "round"); @@ -68,10 +68,9 @@ void MapWindow::initLayers() { if (!m_map->layerExists("navLayer")) { qDebug() << "Initializing navLayer"; QVariantMap nav; - nav["id"] = "navLayer"; nav["type"] = "line"; nav["source"] = "navSource"; - m_map->addLayer(nav, "road-intersection"); + m_map->addLayer("navLayer", nav, "road-intersection"); QVariantMap transition; transition["duration"] = 400; // ms @@ -84,10 +83,9 @@ void MapWindow::initLayers() { qDebug() << "Initializing pinLayer"; m_map->addImage("default_marker", QImage("../assets/navigation/default_marker.svg")); QVariantMap pin; - pin["id"] = "pinLayer"; pin["type"] = "symbol"; pin["source"] = "pinSource"; - m_map->addLayer(pin); + m_map->addLayer("pinLayer", pin); m_map->setLayoutProperty("pinLayer", "icon-pitch-alignment", "viewport"); m_map->setLayoutProperty("pinLayer", "icon-image", "default_marker"); m_map->setLayoutProperty("pinLayer", "icon-ignore-placement", true); @@ -100,10 +98,9 @@ void MapWindow::initLayers() { m_map->addImage("label-arrow", QImage("../assets/images/triangle.svg")); QVariantMap carPos; - carPos["id"] = "carPosLayer"; carPos["type"] = "symbol"; carPos["source"] = "carPosSource"; - m_map->addLayer(carPos); + m_map->addLayer("carPosLayer", carPos); m_map->setLayoutProperty("carPosLayer", "icon-pitch-alignment", "map"); m_map->setLayoutProperty("carPosLayer", "icon-image", "label-arrow"); m_map->setLayoutProperty("carPosLayer", "icon-size", 0.5); @@ -149,7 +146,7 @@ void MapWindow::updateState(const UIState &s) { locationd_valid = (locationd_pos.getValid() && locationd_orientation.getValid() && locationd_velocity.getValid() && pos_accurate_enough); if (locationd_valid) { - last_position = QMapbox::Coordinate(locationd_pos.getValue()[0], locationd_pos.getValue()[1]); + last_position = QMapLibre::Coordinate(locationd_pos.getValue()[0], locationd_pos.getValue()[1]); last_bearing = RAD2DEG(locationd_orientation.getValue()[2]); velocity_filter.update(std::max(10.0, locationd_velocity.getValue()[0])); } @@ -186,10 +183,10 @@ void MapWindow::updateState(const UIState &s) { if (locationd_valid) { // Update current location marker auto point = coordinate_to_collection(*last_position); - QMapbox::Feature feature1(QMapbox::Feature::PointType, point, {}, {}); + QMapLibre::Feature feature1(QMapLibre::Feature::PointType, point, {}, {}); QVariantMap carPosSource; carPosSource["type"] = "geojson"; - carPosSource["data"] = QVariant::fromValue(feature1); + carPosSource["data"] = QVariant::fromValue(feature1); m_map->updateSource("carPosSource", carPosSource); // Map bearing isn't updated when interacting, keep location marker up to date @@ -230,10 +227,10 @@ void MapWindow::updateState(const UIState &s) { qWarning() << "Updating navLayer with new route"; auto route = sm["navRoute"].getNavRoute(); auto route_points = capnp_coordinate_list_to_collection(route.getCoordinates()); - QMapbox::Feature feature(QMapbox::Feature::LineStringType, route_points, {}, {}); + QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); QVariantMap navSource; navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); + navSource["data"] = QVariant::fromValue(feature); m_map->updateSource("navSource", navSource); m_map->setLayoutProperty("navLayer", "visibility", "visible"); @@ -256,24 +253,24 @@ void MapWindow::resizeGL(int w, int h) { } void MapWindow::initializeGL() { - m_map.reset(new QMapboxGL(this, m_settings, size(), 1)); + m_map.reset(new QMapLibre::Map(this, m_settings, size(), 1)); if (last_position) { m_map->setCoordinateZoom(*last_position, MAX_ZOOM); } else { - m_map->setCoordinateZoom(QMapbox::Coordinate(64.31990695292795, -149.79038934046247), MIN_ZOOM); + m_map->setCoordinateZoom(QMapLibre::Coordinate(64.31990695292795, -149.79038934046247), MIN_ZOOM); } m_map->setMargins({0, 350, 0, 50}); m_map->setPitch(MIN_PITCH); m_map->setStyleUrl("mapbox://styles/commaai/clkqztk0f00ou01qyhsa5bzpj"); - QObject::connect(m_map.data(), &QMapboxGL::mapChanged, [=](QMapboxGL::MapChange change) { + QObject::connect(m_map.data(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { // set global animation duration to 0 ms so visibility changes are instant - if (change == QMapboxGL::MapChange::MapChangeDidFinishLoadingStyle) { + if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingStyle) { m_map->setTransitionOptions(0, 0); } - if (change == QMapboxGL::MapChange::MapChangeDidFinishLoadingMap) { + if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingMap) { loaded_once = true; } }); @@ -381,10 +378,10 @@ void MapWindow::updateDestinationMarker() { auto nav_dest = coordinate_from_param("NavDestination"); if (nav_dest.has_value()) { auto point = coordinate_to_collection(*nav_dest); - QMapbox::Feature feature(QMapbox::Feature::PointType, point, {}, {}); + QMapLibre::Feature feature(QMapLibre::Feature::PointType, point, {}, {}); QVariantMap pinSource; pinSource["type"] = "geojson"; - pinSource["data"] = QVariant::fromValue(feature); + pinSource["data"] = QVariant::fromValue(feature); m_map->updateSource("pinSource", pinSource); m_map->setPaintProperty("pinLayer", "visibility", "visible"); } else { diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h index 5fe79f8b15..81ba50037a 100644 --- a/selfdrive/ui/qt/maps/map.h +++ b/selfdrive/ui/qt/maps/map.h @@ -6,7 +6,8 @@ #include #include #include -#include +#include +#include #include #include #include @@ -27,7 +28,7 @@ class MapWindow : public QOpenGLWidget { Q_OBJECT public: - MapWindow(const QMapboxGLSettings &); + MapWindow(const QMapLibre::Settings &); ~MapWindow(); private: @@ -35,8 +36,8 @@ private: void paintGL() final; void resizeGL(int w, int h) override; - QMapboxGLSettings m_settings; - QScopedPointer m_map; + QMapLibre::Settings m_settings; + QScopedPointer m_map; void initLayers(); @@ -56,8 +57,8 @@ private: int interaction_counter = 0; // Position - std::optional last_valid_nav_dest; - std::optional last_position; + std::optional last_valid_nav_dest; + std::optional last_position; std::optional last_bearing; FirstOrderFilter velocity_filter; bool locationd_valid = false; diff --git a/selfdrive/ui/qt/maps/map_eta.cc b/selfdrive/ui/qt/maps/map_eta.cc index 322861ed15..161844c618 100644 --- a/selfdrive/ui/qt/maps/map_eta.cc +++ b/selfdrive/ui/qt/maps/map_eta.cc @@ -20,7 +20,7 @@ void MapETA::paintEvent(QPaintEvent *event) { QPainter p(this); p.setRenderHint(QPainter::Antialiasing); p.setPen(Qt::NoPen); - p.setBrush(QColor(0, 0, 0, 150)); + p.setBrush(QColor(0, 0, 0, 255)); QSizeF txt_size = eta_doc.size(); p.drawRoundedRect((width() - txt_size.width()) / 2 - UI_BORDER_SIZE, 0, txt_size.width() + UI_BORDER_SIZE * 2, height() + 25, 25, 25); p.translate((width() - txt_size.width()) / 2, (height() - txt_size.height()) / 2); diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index 022355e3ce..3907ff7b05 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -16,24 +16,25 @@ QString get_mapbox_token() { return MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; } -QMapboxGLSettings get_mapbox_settings() { - QMapboxGLSettings settings; +QMapLibre::Settings get_mapbox_settings() { + QMapLibre::Settings settings; + settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); if (!Hardware::PC()) { settings.setCacheDatabasePath(MAPS_CACHE_PATH); settings.setCacheDatabaseMaximumSize(100 * 1024 * 1024); } settings.setApiBaseUrl(MAPS_HOST); - settings.setAccessToken(get_mapbox_token()); + settings.setApiKey(get_mapbox_token()); return settings; } -QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in) { +QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in) { return QGeoCoordinate(in.first, in.second); } -QMapbox::CoordinatesCollections model_to_collection( +QMapLibre::CoordinatesCollections model_to_collection( const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, const cereal::XYZTData::Reader &line){ @@ -42,7 +43,7 @@ QMapbox::CoordinatesCollections model_to_collection( Eigen::Vector3d orient(calibratedOrientationECEF.getValue()[0], calibratedOrientationECEF.getValue()[1], calibratedOrientationECEF.getValue()[2]); Eigen::Matrix3d ecef_from_local = euler2rot(orient); - QMapbox::Coordinates coordinates; + QMapLibre::Coordinates coordinates; auto x = line.getX(); auto y = line.getY(); auto z = line.getZ(); @@ -52,28 +53,28 @@ QMapbox::CoordinatesCollections model_to_collection( coordinates.push_back({point_geodetic.lat, point_geodetic.lon}); } - return {QMapbox::CoordinatesCollection{coordinates}}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } -QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c) { - QMapbox::Coordinates coordinates{c}; - return {QMapbox::CoordinatesCollection{coordinates}}; +QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c) { + QMapLibre::Coordinates coordinates{c}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } -QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader& coordinate_list) { - QMapbox::Coordinates coordinates; +QMapLibre::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader& coordinate_list) { + QMapLibre::Coordinates coordinates; for (auto const &c : coordinate_list) { coordinates.push_back({c.getLatitude(), c.getLongitude()}); } - return {QMapbox::CoordinatesCollection{coordinates}}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } -QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { - QMapbox::Coordinates coordinates; +QMapLibre::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { + QMapLibre::Coordinates coordinates; for (auto &c : coordinate_list) { coordinates.push_back({c.latitude(), c.longitude()}); } - return {QMapbox::CoordinatesCollection{coordinates}}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } QList polyline_to_coordinate_list(const QString &polylineString) { @@ -118,7 +119,7 @@ QList polyline_to_coordinate_list(const QString &polylineString) return path; } -std::optional coordinate_from_param(const std::string ¶m) { +std::optional coordinate_from_param(const std::string ¶m) { QString json_str = QString::fromStdString(Params().get(param)); if (json_str.isEmpty()) return {}; @@ -127,7 +128,7 @@ std::optional coordinate_from_param(const std::string ¶ QJsonObject json = doc.object(); if (json["latitude"].isDouble() && json["longitude"].isDouble()) { - QMapbox::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble()); + QMapLibre::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble()); return coord; } else { return {}; diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h index 4d6e9b5382..0f4be674f0 100644 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ b/selfdrive/ui/qt/maps/map_helpers.h @@ -3,8 +3,9 @@ #include #include #include +#include +#include #include -#include #include #include "common/util.h" @@ -17,15 +18,15 @@ const QString MAPS_HOST = util::getenv("MAPS_HOST", MAPBOX_TOKEN.isEmpty() ? "ht const QString MAPS_CACHE_PATH = "/data/mbgl-cache-navd.db"; QString get_mapbox_token(); -QMapboxGLSettings get_mapbox_settings(); -QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in); -QMapbox::CoordinatesCollections model_to_collection( +QMapLibre::Settings get_mapbox_settings(); +QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in); +QMapLibre::CoordinatesCollections model_to_collection( const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, const cereal::XYZTData::Reader &line); -QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c); -QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); -QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list); +QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c); +QMapLibre::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); +QMapLibre::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list); QList polyline_to_coordinate_list(const QString &polylineString); -std::optional coordinate_from_param(const std::string ¶m); +std::optional coordinate_from_param(const std::string ¶m); std::pair map_format_distance(float d, bool is_metric); diff --git a/selfdrive/ui/qt/maps/map_panel.cc b/selfdrive/ui/qt/maps/map_panel.cc index 0a2286ff6f..c4cc20e21d 100644 --- a/selfdrive/ui/qt/maps/map_panel.cc +++ b/selfdrive/ui/qt/maps/map_panel.cc @@ -8,7 +8,7 @@ #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/ui.h" -MapPanel::MapPanel(const QMapboxGLSettings &mapboxSettings, QWidget *parent) : QFrame(parent) { +MapPanel::MapPanel(const QMapLibre::Settings &mapboxSettings, QWidget *parent) : QFrame(parent) { content_stack = new QStackedLayout(this); content_stack->setContentsMargins(0, 0, 0, 0); diff --git a/selfdrive/ui/qt/maps/map_panel.h b/selfdrive/ui/qt/maps/map_panel.h index 43a2cc7c89..190bb63446 100644 --- a/selfdrive/ui/qt/maps/map_panel.h +++ b/selfdrive/ui/qt/maps/map_panel.h @@ -1,14 +1,14 @@ #pragma once #include -#include +#include #include class MapPanel : public QFrame { Q_OBJECT public: - explicit MapPanel(const QMapboxGLSettings &settings, QWidget *parent = nullptr); + explicit MapPanel(const QMapLibre::Settings &settings, QWidget *parent = nullptr); signals: void mapPanelRequested(); diff --git a/selfdrive/ui/qt/network/networking.cc b/selfdrive/ui/qt/network/networking.cc index 090b9b578c..5354a01fa0 100644 --- a/selfdrive/ui/qt/network/networking.cc +++ b/selfdrive/ui/qt/network/networking.cc @@ -48,6 +48,7 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { an = new AdvancedNetworking(this, wifi); connect(an, &AdvancedNetworking::backPress, [=]() { main_layout->setCurrentWidget(wifiScreen); }); + connect(an, &AdvancedNetworking::requestWifiScreen, [=]() { main_layout->setCurrentWidget(wifiScreen); }); main_layout->addWidget(an); QPalette pal = palette(); @@ -181,6 +182,25 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid }); list->addItem(meteredToggle); + // Hidden Network + hiddenNetworkButton = new ButtonControl(tr("Hidden Network"), tr("CONNECT")); + connect(hiddenNetworkButton, &ButtonControl::clicked, [=]() { + QString ssid = InputDialog::getText(tr("Enter SSID"), this, "", false, 1); + if (!ssid.isEmpty()) { + QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"%1\"").arg(ssid), true, -1); + Network hidden_network; + hidden_network.ssid = ssid.toUtf8(); + if (!pass.isEmpty()) { + hidden_network.security_type = SecurityType::WPA; + wifi->connect(hidden_network, pass); + } else { + wifi->connect(hidden_network); + } + emit requestWifiScreen(); + } + }); + list->addItem(hiddenNetworkButton); + // Set initial config wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn")), metered); diff --git a/selfdrive/ui/qt/network/networking.h b/selfdrive/ui/qt/network/networking.h index 4ff7380f42..9b6af005ea 100644 --- a/selfdrive/ui/qt/network/networking.h +++ b/selfdrive/ui/qt/network/networking.h @@ -62,12 +62,14 @@ private: ToggleControl* tetheringToggle; ToggleControl* roamingToggle; ButtonControl* editApnButton; + ButtonControl* hiddenNetworkButton; ToggleControl* meteredToggle; WifiManager* wifi = nullptr; Params params; signals: void backPress(); + void requestWifiScreen(); public slots: void toggleTethering(bool enabled); diff --git a/selfdrive/ui/qt/network/wifi_manager.cc b/selfdrive/ui/qt/network/wifi_manager.cc index 03c6896f7a..ebb5cb8736 100644 --- a/selfdrive/ui/qt/network/wifi_manager.cc +++ b/selfdrive/ui/qt/network/wifi_manager.cc @@ -59,6 +59,8 @@ WifiManager::WifiManager(QObject *parent) : QObject(parent) { } timer.callOnTimeout(this, &WifiManager::requestScan); + + initConnections(); } void WifiManager::setup() { @@ -72,7 +74,6 @@ void WifiManager::setup() { raw_adapter_state = call(adapter, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE, "State"); activeAp = call(adapter, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE_WIRELESS, "ActiveAccessPoint").path(); - initConnections(); requestScan(); } diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index 693a0253b4..df9bb24651 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -3,62 +3,39 @@ #include #include -#include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/util.h" const int FACE_IMG_SIZE = 130; -DriverViewWindow::DriverViewWindow(QWidget* parent) : QWidget(parent) { - setAttribute(Qt::WA_OpaquePaintEvent); - layout = new QStackedLayout(this); - layout->setStackingMode(QStackedLayout::StackAll); - - cameraView = new CameraWidget("camerad", VISION_STREAM_DRIVER, true, this); - layout->addWidget(cameraView); - - scene = new DriverViewScene(this); - connect(cameraView, &CameraWidget::vipcThreadFrameReceived, scene, &DriverViewScene::frameUpdated); - layout->addWidget(scene); - layout->setCurrentWidget(scene); - - QObject::connect(device(), &Device::interactiveTimeout, this, &DriverViewWindow::closeView); -} - -void DriverViewWindow::closeView() { - if (isVisible()) { - cameraView->stopVipcThread(); - emit done(); - } -} - -void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) { - closeView(); -} - -DriverViewScene::DriverViewScene(QWidget* parent) : QWidget(parent) { +DriverViewWindow::DriverViewWindow(QWidget* parent) : CameraWidget("camerad", VISION_STREAM_DRIVER, true, parent) { face_img = loadPixmap("../assets/img_driver_face_static.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); + QObject::connect(this, &CameraWidget::clicked, this, &DriverViewWindow::done); + QObject::connect(device(), &Device::interactiveTimeout, this, [this]() { + if (isVisible()) { + emit done(); + } + }); } -void DriverViewScene::showEvent(QShowEvent* event) { - frame_updated = false; +void DriverViewWindow::showEvent(QShowEvent* event) { params.putBool("IsDriverViewEnabled", true); device()->resetInteractiveTimeout(60); + CameraWidget::showEvent(event); } -void DriverViewScene::hideEvent(QHideEvent* event) { +void DriverViewWindow::hideEvent(QHideEvent* event) { params.putBool("IsDriverViewEnabled", false); + stopVipcThread(); + CameraWidget::hideEvent(event); } -void DriverViewScene::frameUpdated() { - frame_updated = true; - update(); -} +void DriverViewWindow::paintGL() { + CameraWidget::paintGL(); -void DriverViewScene::paintEvent(QPaintEvent* event) { + std::lock_guard lk(frame_lock); QPainter p(this); - // startup msg - if (!frame_updated) { + if (frames.empty()) { p.setPen(Qt::white); p.setRenderHint(QPainter::TextAntialiasing); p.setFont(InterFont(100, QFont::Bold)); @@ -68,10 +45,8 @@ void DriverViewScene::paintEvent(QPaintEvent* event) { const auto &sm = *(uiState()->sm); cereal::DriverStateV2::Reader driver_state = sm["driverStateV2"].getDriverStateV2(); - cereal::DriverStateV2::DriverData::Reader driver_data; - - is_rhd = driver_state.getWheelOnRightProb() > 0.5; - driver_data = is_rhd ? driver_state.getRightDriverData() : driver_state.getLeftDriverData(); + bool is_rhd = driver_state.getWheelOnRightProb() > 0.5; + auto driver_data = is_rhd ? driver_state.getRightDriverData() : driver_state.getLeftDriverData(); bool face_detected = driver_data.getFaceProb() > 0.7; if (face_detected) { diff --git a/selfdrive/ui/qt/offroad/driverview.h b/selfdrive/ui/qt/offroad/driverview.h index 8bfc7a4b7b..155e4ede32 100644 --- a/selfdrive/ui/qt/offroad/driverview.h +++ b/selfdrive/ui/qt/offroad/driverview.h @@ -1,44 +1,21 @@ #pragma once -#include - #include "selfdrive/ui/qt/widgets/cameraview.h" -class DriverViewScene : public QWidget { +class DriverViewWindow : public CameraWidget { Q_OBJECT public: - explicit DriverViewScene(QWidget *parent); + explicit DriverViewWindow(QWidget *parent); -public slots: - void frameUpdated(); +signals: + void done(); protected: void showEvent(QShowEvent *event) override; void hideEvent(QHideEvent *event) override; - void paintEvent(QPaintEvent *event) override; + void paintGL() override; -private: Params params; QPixmap face_img; - bool is_rhd = false; - bool frame_updated = false; -}; - -class DriverViewWindow : public QWidget { - Q_OBJECT - -public: - explicit DriverViewWindow(QWidget *parent); - -signals: - void done(); - -protected: - void mouseReleaseEvent(QMouseEvent* e) override; - void closeView(); - - CameraWidget *cameraView; - DriverViewScene *scene; - QStackedLayout *layout; }; diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc index c7c22f0ea3..b1219055fd 100644 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ b/selfdrive/ui/qt/offroad/onboarding.cc @@ -183,7 +183,7 @@ void DeclinePage::showEvent(QShowEvent *event) { void OnboardingWindow::updateActiveScreen() { if (!accepted_terms) { setCurrentIndex(0); - } else if (!training_done && !params.getBool("Passive")) { + } else if (!training_done) { setCurrentIndex(1); } else { emit onboardingDone(); @@ -199,7 +199,7 @@ OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) { TermsPage* terms = new TermsPage(this); addWidget(terms); connect(terms, &TermsPage::acceptedTerms, [=]() { - Params().put("HasAcceptedTerms", current_terms_version); + params.put("HasAcceptedTerms", current_terms_version); accepted_terms = true; updateActiveScreen(); }); @@ -209,7 +209,7 @@ OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) { addWidget(tr); connect(tr, &TrainingGuide::completedTraining, [=]() { training_done = true; - Params().put("CompletedTrainingVersion", current_training_version); + params.put("CompletedTrainingVersion", current_training_version); updateActiveScreen(); }); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 669de5eae9..85393cabc0 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -215,15 +215,13 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { }); addItem(resetCalibBtn); - if (!params.getBool("Passive")) { - auto retrainingBtn = new ButtonControl(tr("Review Training Guide"), tr("REVIEW"), tr("Review the rules, features, and limitations of openpilot")); - connect(retrainingBtn, &ButtonControl::clicked, [=]() { - if (ConfirmationDialog::confirm(tr("Are you sure you want to review the training guide?"), tr("Review"), this)) { - emit reviewTrainingGuide(); - } - }); - addItem(retrainingBtn); - } + auto retrainingBtn = new ButtonControl(tr("Review Training Guide"), tr("REVIEW"), tr("Review the rules, features, and limitations of openpilot")); + connect(retrainingBtn, &ButtonControl::clicked, [=]() { + if (ConfirmationDialog::confirm(tr("Are you sure you want to review the training guide?"), tr("Review"), this)) { + emit reviewTrainingGuide(); + } + }); + addItem(retrainingBtn); if (Hardware::TICI()) { auto regulatoryBtn = new ButtonControl(tr("Regulatory"), tr("VIEW"), ""); @@ -347,7 +345,6 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { // setup two main layouts sidebar_widget = new QWidget; QVBoxLayout *sidebar_layout = new QVBoxLayout(sidebar_widget); - sidebar_layout->setMargin(0); panel_widget = new QStackedWidget(); // close button @@ -356,7 +353,6 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { QPushButton { font-size: 140px; padding-bottom: 20px; - border 1px grey solid; border-radius: 100px; background-color: #292929; font-weight: 400; diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 971eb673e2..01750eaf2f 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -9,6 +9,7 @@ #include #include +#include "common/swaglog.h" #include "common/timing.h" #include "selfdrive/ui/qt/util.h" #ifdef ENABLE_MAPS @@ -288,7 +289,7 @@ void AnnotatedCameraWidget::updateState(const UIState &s) { const auto nav_instruction = sm["navInstruction"].getNavInstruction(); // Handle older routes where vCruiseCluster is not set - float v_cruise = cs.getVCruiseCluster() == 0.0 ? cs.getVCruise() : cs.getVCruiseCluster(); + float v_cruise = cs.getVCruiseCluster() == 0.0 ? cs.getVCruise() : cs.getVCruiseCluster(); setSpeed = cs_alive ? v_cruise : SET_SPEED_NA; is_cruise_set = setSpeed > 0 && (int)setSpeed != SET_SPEED_NA; if (is_cruise_set && !s.scene.is_metric) { @@ -605,7 +606,6 @@ void AnnotatedCameraWidget::paintGL() { SubMaster &sm = *(s->sm); const double start_draw_t = millis_since_boot(); const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2(); - const cereal::RadarState::Reader &radar_state = sm["radarState"].getRadarState(); // draw camera frame { @@ -654,17 +654,13 @@ void AnnotatedCameraWidget::paintGL() { painter.setRenderHint(QPainter::Antialiasing); painter.setPen(Qt::NoPen); - if (s->worldObjectsVisible()) { - if (sm.rcv_frame("modelV2") > s->scene.started_frame) { - update_model(s, model, sm["uiPlan"].getUiPlan()); - if (sm.rcv_frame("radarState") > s->scene.started_frame) { - update_leads(s, radar_state, model.getPosition()); - } - } - + if (s->scene.world_objects_visible) { + update_model(s, model, sm["uiPlan"].getUiPlan()); drawLaneLines(painter, s); - if (s->scene.longitudinal_control) { + if (s->scene.longitudinal_control && sm.rcv_frame("radarState") > s->scene.started_frame) { + auto radar_state = sm["radarState"].getRadarState(); + update_leads(s, radar_state, model.getPosition()); auto lead_one = radar_state.getLeadOne(); auto lead_two = radar_state.getLeadTwo(); if (lead_one.getStatus()) { diff --git a/selfdrive/ui/qt/setup/reset.cc b/selfdrive/ui/qt/setup/reset.cc index 7999dd640b..c9e0525784 100644 --- a/selfdrive/ui/qt/setup/reset.cc +++ b/selfdrive/ui/qt/setup/reset.cc @@ -57,7 +57,7 @@ Reset::Reset(ResetMode mode, QWidget *parent) : QWidget(parent) { main_layout->addSpacing(60); - body = new QLabel(tr("Press confirm to erase all content and settings. Press cancel to resume boot.")); + body = new QLabel(tr("System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.")); body->setWordWrap(true); body->setStyleSheet("font-size: 80px; font-weight: light;"); main_layout->addWidget(body, 1, Qt::AlignTop | Qt::AlignLeft); @@ -97,11 +97,6 @@ Reset::Reset(ResetMode mode, QWidget *parent) : QWidget(parent) { body->setText(tr("Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.")); } - // automatically start if we're just finishing up an ABL reset - if (mode == ResetMode::FORMAT) { - startReset(); - } - setStyleSheet(R"( * { font-family: Inter; @@ -129,8 +124,6 @@ int main(int argc, char *argv[]) { if (argc > 1) { if (strcmp(argv[1], "--recover") == 0) { mode = ResetMode::RECOVER; - } else if (strcmp(argv[1], "--format") == 0) { - mode = ResetMode::FORMAT; } } diff --git a/selfdrive/ui/qt/setup/reset.h b/selfdrive/ui/qt/setup/reset.h index 04a191d829..8bf368e3e8 100644 --- a/selfdrive/ui/qt/setup/reset.h +++ b/selfdrive/ui/qt/setup/reset.h @@ -5,7 +5,6 @@ enum ResetMode { USER_RESET, // user initiated a factory reset from openpilot RECOVER, // userdata is corrupt for some reason, give a chance to recover - FORMAT, // finish up an ABL factory reset }; class Reset : public QWidget { diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index 3b3666b19a..4f2e4f48cb 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -20,7 +20,7 @@ #include "selfdrive/ui/qt/widgets/input.h" const std::string USER_AGENT = "AGNOSSetup-"; -const QString DASHCAM_URL = "https://dashcam.comma.ai"; +const QString TEST_URL = "https://openpilot.comma.ai"; bool is_elf(char *fname) { FILE *fp = fopen(fname, "rb"); @@ -34,6 +34,11 @@ bool is_elf(char *fname) { } void Setup::download(QString url) { + // autocomplete incomplete urls + if (QRegularExpression("^([^/.]+)/([^/]+)$").match(url).hasMatch()) { + url.prepend("https://installer.comma.ai/"); + } + CURL *curl = curl_easy_init(); if (!curl) { emit finished(url, tr("Something went wrong. Reboot the device.")); @@ -224,11 +229,11 @@ QWidget * Setup::network_setup() { } repaint(); }); - request->sendRequest(DASHCAM_URL); + request->sendRequest(TEST_URL); QTimer *timer = new QTimer(this); QObject::connect(timer, &QTimer::timeout, [=]() { if (!request->active() && cont->isVisible()) { - request->sendRequest(DASHCAM_URL); + request->sendRequest(TEST_URL); } }); timer->start(1000); diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 78da183503..bc3c494fa7 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -5,6 +5,7 @@ #include #include +#include #include #include #include @@ -25,7 +26,7 @@ QString getVersion() { } QString getBrand() { - return Params().getBool("Passive") ? QObject::tr("dashcam") : QObject::tr("openpilot"); + return QObject::tr("openpilot"); } QString getUserAgent() { @@ -112,6 +113,13 @@ void initApp(int argc, char *argv[], bool disable_hidpi) { #endif } + qputenv("QT_DBL_CLICK_DIST", QByteArray::number(150)); + + // ensure the current dir matches the exectuable's directory + QApplication tmp(argc, argv); + QString appDir = QCoreApplication::applicationDirPath(); + QDir::setCurrent(appDir); + setQtSurfaceFormat(); } diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 6a5064e8ca..7b1f2f1d24 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -31,8 +31,8 @@ const char frame_vertex_shader[] = " vTexCoord = aTexCoord;\n" "}\n"; -#ifdef QCOM2 const char frame_fragment_shader[] = +#ifdef QCOM2 "#version 300 es\n" "#extension GL_OES_EGL_image_external_essl3 : enable\n" "precision mediump float;\n" @@ -43,7 +43,6 @@ const char frame_fragment_shader[] = " colorOut = texture(uTexture, vTexCoord);\n" "}\n"; #else -const char frame_fragment_shader[] = #ifdef __APPLE__ "#version 330 core\n" #else @@ -188,12 +187,23 @@ void CameraWidget::showEvent(QShowEvent *event) { } void CameraWidget::stopVipcThread() { + makeCurrent(); if (vipc_thread) { vipc_thread->requestInterruption(); vipc_thread->quit(); vipc_thread->wait(); vipc_thread = nullptr; } + +#ifdef QCOM2 + EGLDisplay egl_display = eglGetCurrentDisplay(); + assert(egl_display != EGL_NO_DISPLAY); + for (auto &pair : egl_images) { + eglDestroyImageKHR(egl_display, pair.second); + assert(eglGetError() == EGL_SUCCESS); + } + egl_images.clear(); +#endif } void CameraWidget::availableStreamsUpdated(std::set streams) { @@ -324,8 +334,8 @@ void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { stream_stride = vipc_client->buffers[0].stride; #ifdef QCOM2 - egl_display = eglGetCurrentDisplay(); - + EGLDisplay egl_display = eglGetCurrentDisplay(); + assert(egl_display != EGL_NO_DISPLAY); for (auto &pair : egl_images) { eglDestroyImageKHR(egl_display, pair.second); } @@ -416,13 +426,6 @@ void CameraWidget::vipcThread() { } } } - -#ifdef QCOM2 - for (auto &pair : egl_images) { - eglDestroyImageKHR(egl_display, pair.second); - } - egl_images.clear(); -#endif } void CameraWidget::clearFrames() { diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index fcd5b1b18f..c97038cf43 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -70,7 +70,6 @@ protected: QColor bg = QColor("#000000"); #ifdef QCOM2 - EGLDisplay egl_display; std::map egl_images; #endif diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index 87304a4585..40dda971f5 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -12,13 +12,14 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons hlayout->setSpacing(20); // left icon - icon_label = new QLabel(); + icon_label = new QLabel(this); + hlayout->addWidget(icon_label); if (!icon.isEmpty()) { icon_pixmap = QPixmap(icon).scaledToWidth(80, Qt::SmoothTransformation); icon_label->setPixmap(icon_pixmap); icon_label->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); - hlayout->addWidget(icon_label); } + icon_label->setVisible(!icon.isEmpty()); // title title_label = new QPushButton(title); @@ -113,3 +114,28 @@ void ElidedLabel::paintEvent(QPaintEvent *event) { opt.initFrom(this); style()->drawItemText(&painter, contentsRect(), alignment(), opt.palette, isEnabled(), elidedText_, foregroundRole()); } + +// ParamControl + +ParamControl::ParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent) + : ToggleControl(title, desc, icon, false, parent) { + key = param.toStdString(); + QObject::connect(this, &ParamControl::toggleFlipped, this, &ParamControl::toggleClicked); +} + +void ParamControl::toggleClicked(bool state) { + auto do_confirm = [this]() { + QString content("

" + title_label->text() + "


" + "

" + getDescription() + "

"); + return ConfirmationDialog(content, tr("Enable"), tr("Cancel"), true, this).exec(); + }; + + bool confirmed = store_confirm && params.getBool(key + "Confirmed"); + if (!confirm || confirmed || !state || do_confirm()) { + if (store_confirm && state) params.putBool(key + "Confirmed", true); + params.putBool(key, state); + setIcon(state); + } else { + toggle.togglePosition(); + } +} diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index 811595726d..e4630c6590 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -144,24 +144,7 @@ class ParamControl : public ToggleControl { Q_OBJECT public: - ParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent = nullptr) : ToggleControl(title, desc, icon, false, parent) { - key = param.toStdString(); - QObject::connect(this, &ParamControl::toggleFlipped, [=](bool state) { - QString content("

" + title + "


" - "

" + getDescription() + "

"); - ConfirmationDialog dialog(content, tr("Enable"), tr("Cancel"), true, this); - - bool confirmed = store_confirm && params.getBool(key + "Confirmed"); - if (!confirm || confirmed || !state || dialog.exec()) { - if (store_confirm && state) params.putBool(key + "Confirmed", true); - params.putBool(key, state); - setIcon(state); - } else { - toggle.togglePosition(); - } - }); - } - + ParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent = nullptr); void setConfirmation(bool _confirm, bool _store_confirm) { confirm = _confirm; store_confirm = _store_confirm; @@ -184,6 +167,7 @@ public: } private: + void toggleClicked(bool state); void setIcon(bool state) { if (state && !active_icon_pixmap.isNull()) { icon_label->setPixmap(active_icon_pixmap); diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index 52d0c5cd6e..4ff0de29f9 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -129,7 +129,8 @@ InputDialog::InputDialog(const QString &title, QWidget *parent, const QString &s line->setEchoMode(QLineEdit::Normal); } }); - eye_btn->setChecked(true); + eye_btn->toggle(); + eye_btn->setChecked(false); textbox_layout->addWidget(eye_btn); } diff --git a/selfdrive/ui/soundd.py b/selfdrive/ui/soundd.py new file mode 100644 index 0000000000..11caf809d1 --- /dev/null +++ b/selfdrive/ui/soundd.py @@ -0,0 +1,166 @@ +import math +import numpy as np +import time +import wave + +from typing import Dict, Optional, Tuple + +from cereal import car, messaging +from openpilot.common.basedir import BASEDIR +from openpilot.common.filter_simple import FirstOrderFilter +from openpilot.common.realtime import Ratekeeper +from openpilot.common.retry import retry +from openpilot.common.swaglog import cloudlog + +from openpilot.system import micd + +SAMPLE_RATE = 48000 +SAMPLE_BUFFER = 4096 # (approx 100ms) +MAX_VOLUME = 1.0 +MIN_VOLUME = 0.1 +CONTROLS_TIMEOUT = 5 # 5 seconds +FILTER_DT = 1. / (micd.SAMPLE_RATE / micd.FFT_SAMPLES) + +AMBIENT_DB = 30 # DB where MIN_VOLUME is applied +DB_SCALE = 30 # AMBIENT_DB + DB_SCALE is where MAX_VOLUME is applied + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + + +sound_list: Dict[int, Tuple[str, Optional[int], float]] = { + # AudibleAlert, file name, play count (none for infinite) + AudibleAlert.engage: ("engage.wav", 1, MAX_VOLUME), + AudibleAlert.disengage: ("disengage.wav", 1, MAX_VOLUME), + AudibleAlert.refuse: ("refuse.wav", 1, MAX_VOLUME), + + AudibleAlert.prompt: ("prompt.wav", 1, MAX_VOLUME), + AudibleAlert.promptRepeat: ("prompt.wav", None, MAX_VOLUME), + AudibleAlert.promptDistracted: ("prompt_distracted.wav", None, MAX_VOLUME), + + AudibleAlert.warningSoft: ("warning_soft.wav", None, MAX_VOLUME), + AudibleAlert.warningImmediate: ("warning_immediate.wav", None, MAX_VOLUME), +} + +def check_controls_timeout_alert(sm): + controls_missing = time.monotonic() - sm.recv_time['controlsState'] + + if controls_missing > CONTROLS_TIMEOUT: + if sm['controlsState'].enabled and (controls_missing - CONTROLS_TIMEOUT) < 10: + return True + + return False + + +class Soundd: + def __init__(self): + self.load_sounds() + + self.current_alert = AudibleAlert.none + self.current_volume = MIN_VOLUME + self.current_sound_frame = 0 + + self.controls_timeout_alert = False + + self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False) + + def load_sounds(self): + self.loaded_sounds: Dict[int, np.ndarray] = {} + + # Load all sounds + for sound in sound_list: + filename, play_count, volume = sound_list[sound] + + wavefile = wave.open(BASEDIR + "/selfdrive/assets/sounds/" + filename, 'r') + + assert wavefile.getnchannels() == 1 + assert wavefile.getsampwidth() == 2 + assert wavefile.getframerate() == SAMPLE_RATE + + length = wavefile.getnframes() + self.loaded_sounds[sound] = np.frombuffer(wavefile.readframes(length), dtype=np.int16).astype(np.float32) / (2**16/2) + + def get_sound_data(self, frames): # get "frames" worth of data from the current alert sound, looping when required + + ret = np.zeros(frames, dtype=np.float32) + + if self.current_alert != AudibleAlert.none: + num_loops = sound_list[self.current_alert][1] + sound_data = self.loaded_sounds[self.current_alert] + written_frames = 0 + + current_sound_frame = self.current_sound_frame % len(sound_data) + loops = self.current_sound_frame // len(sound_data) + + while written_frames < frames and (num_loops is None or loops < num_loops): + available_frames = sound_data.shape[0] - current_sound_frame + frames_to_write = min(available_frames, frames - written_frames) + ret[written_frames:written_frames+frames_to_write] = sound_data[current_sound_frame:current_sound_frame+frames_to_write] + written_frames += frames_to_write + self.current_sound_frame += frames_to_write + + return ret * self.current_volume + + def callback(self, data_out: np.ndarray, frames: int, time, status) -> None: + if status: + cloudlog.warning(f"soundd stream over/underflow: {status}") + data_out[:frames, 0] = self.get_sound_data(frames) + + def update_alert(self, new_alert): + current_alert_played_once = self.current_alert == AudibleAlert.none or self.current_sound_frame > len(self.loaded_sounds[self.current_alert]) + if self.current_alert != new_alert and (new_alert != AudibleAlert.none or current_alert_played_once): + self.current_alert = new_alert + self.current_sound_frame = 0 + + def get_audible_alert(self, sm): + if sm.updated['controlsState']: + new_alert = sm['controlsState'].alertSound.raw + self.update_alert(new_alert) + elif check_controls_timeout_alert(sm): + self.update_alert(AudibleAlert.warningImmediate) + self.controls_timeout_alert = True + elif self.controls_timeout_alert: + self.update_alert(AudibleAlert.none) + self.controls_timeout_alert = False + + def calculate_volume(self, weighted_db): + volume = ((weighted_db - AMBIENT_DB) / DB_SCALE) * (MAX_VOLUME - MIN_VOLUME) + MIN_VOLUME + return math.pow(10, (np.clip(volume, MIN_VOLUME, MAX_VOLUME) - 1)) + + @retry(attempts=7, delay=3) + def get_stream(self, sd): + # reload sounddevice to reinitialize portaudio + sd._terminate() + sd._initialize() + return sd.OutputStream(channels=1, samplerate=SAMPLE_RATE, callback=self.callback, blocksize=SAMPLE_BUFFER) + + def soundd_thread(self): + # sounddevice must be imported after forking processes + import sounddevice as sd + + sm = messaging.SubMaster(['controlsState', 'microphone']) + + with self.get_stream(sd) as stream: + rk = Ratekeeper(20) + + cloudlog.info(f"soundd stream started: {stream.samplerate=} {stream.channels=} {stream.dtype=} {stream.device=}, {stream.blocksize=}") + while True: + sm.update(0) + + if sm.updated['microphone'] and self.current_alert == AudibleAlert.none: # only update volume filter when not playing alert + self.spl_filter_weighted.update(sm["microphone"].soundPressureWeightedDb) + self.current_volume = self.calculate_volume(float(self.spl_filter_weighted.x)) + + self.get_audible_alert(sm) + + rk.keep_time() + + assert stream.active + + +def main(): + s = Soundd() + s.soundd_thread() + + +if __name__ == "__main__": + main() diff --git a/selfdrive/ui/soundd/.gitignore b/selfdrive/ui/soundd/.gitignore deleted file mode 100644 index c47f949d37..0000000000 --- a/selfdrive/ui/soundd/.gitignore +++ /dev/null @@ -1 +0,0 @@ -_soundd diff --git a/selfdrive/ui/soundd/main.cc b/selfdrive/ui/soundd/main.cc deleted file mode 100644 index c6c7434ca4..0000000000 --- a/selfdrive/ui/soundd/main.cc +++ /dev/null @@ -1,18 +0,0 @@ -#include - -#include - -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/soundd/sound.h" - -int main(int argc, char **argv) { - qInstallMessageHandler(swagLogMessageHandler); - setpriority(PRIO_PROCESS, 0, -20); - - QApplication a(argc, argv); - std::signal(SIGINT, sigTermHandler); - std::signal(SIGTERM, sigTermHandler); - - Sound sound; - return a.exec(); -} diff --git a/selfdrive/ui/soundd/sound.cc b/selfdrive/ui/soundd/sound.cc deleted file mode 100644 index a5884f113f..0000000000 --- a/selfdrive/ui/soundd/sound.cc +++ /dev/null @@ -1,67 +0,0 @@ -#include "selfdrive/ui/soundd/sound.h" - -#include - -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/util.h" - -// TODO: detect when we can't play sounds -// TODO: detect when we can't display the UI - -Sound::Sound(QObject *parent) : sm({"controlsState", "microphone"}) { - qInfo() << "default audio device: " << QAudioDeviceInfo::defaultOutputDevice().deviceName(); - - for (auto &[alert, fn, loops, volume] : sound_list) { - QSoundEffect *s = new QSoundEffect(this); - QObject::connect(s, &QSoundEffect::statusChanged, [=]() { - assert(s->status() != QSoundEffect::Error); - }); - s->setSource(QUrl::fromLocalFile("../../assets/sounds/" + fn)); - s->setVolume(volume); - sounds[alert] = {s, loops}; - } - - QTimer *timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, this, &Sound::update); - timer->start(1000 / UI_FREQ); -} - -void Sound::update() { - sm.update(0); - - // scale volume using ambient noise level - if (sm.updated("microphone")) { - float volume = util::map_val(sm["microphone"].getMicrophone().getFilteredSoundPressureWeightedDb(), 30.f, 60.f, 0.f, 1.f); - volume = QAudio::convertVolume(volume, QAudio::LogarithmicVolumeScale, QAudio::LinearVolumeScale); - // set volume on changes - if (std::exchange(current_volume, std::nearbyint(volume * 10)) != current_volume) { - Hardware::set_volume(volume); - } - } - - setAlert(Alert::get(sm, 0)); -} - -void Sound::setAlert(const Alert &alert) { - if (!current_alert.equal(alert)) { - current_alert = alert; - // stop sounds - for (auto &[s, loops] : sounds) { - // Only stop repeating sounds - if (s->loopsRemaining() > 1 || s->loopsRemaining() == QSoundEffect::Infinite) { - s->stop(); - } - } - - // play sound - if (alert.sound != AudibleAlert::NONE) { - auto &[s, loops] = sounds[alert.sound]; - s->setLoopCount(loops); - s->play(); - } - } -} diff --git a/selfdrive/ui/soundd/sound.h b/selfdrive/ui/soundd/sound.h deleted file mode 100644 index 4fcb2e1bce..0000000000 --- a/selfdrive/ui/soundd/sound.h +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/ui.h" - - -const float MAX_VOLUME = 1.0; - -const std::tuple sound_list[] = { - // AudibleAlert, file name, loop count - {AudibleAlert::ENGAGE, "engage.wav", 0, MAX_VOLUME}, - {AudibleAlert::DISENGAGE, "disengage.wav", 0, MAX_VOLUME}, - {AudibleAlert::REFUSE, "refuse.wav", 0, MAX_VOLUME}, - - {AudibleAlert::PROMPT, "prompt.wav", 0, MAX_VOLUME}, - {AudibleAlert::PROMPT_REPEAT, "prompt.wav", QSoundEffect::Infinite, MAX_VOLUME}, - {AudibleAlert::PROMPT_DISTRACTED, "prompt_distracted.wav", QSoundEffect::Infinite, MAX_VOLUME}, - - {AudibleAlert::WARNING_SOFT, "warning_soft.wav", QSoundEffect::Infinite, MAX_VOLUME}, - {AudibleAlert::WARNING_IMMEDIATE, "warning_immediate.wav", QSoundEffect::Infinite, MAX_VOLUME}, -}; - -class Sound : public QObject { -public: - explicit Sound(QObject *parent = 0); - -protected: - void update(); - void setAlert(const Alert &alert); - - SubMaster sm; - Alert current_alert = {}; - QMap> sounds; - int current_volume = -1; -}; diff --git a/selfdrive/ui/soundd/soundd b/selfdrive/ui/soundd/soundd deleted file mode 100755 index 9b7a32fec9..0000000000 --- a/selfdrive/ui/soundd/soundd +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/sh -cd "$(dirname "$0")" -export QT_QPA_PLATFORM="offscreen" -exec ./_soundd diff --git a/selfdrive/ui/spinner b/selfdrive/ui/spinner index 35feab3f7e..965c8f581a 100755 --- a/selfdrive/ui/spinner +++ b/selfdrive/ui/spinner @@ -1,7 +1,7 @@ #!/bin/sh -if [ -f /TICI ] && [ ! -f qt/spinner ]; then - cp qt/spinner_larch64 qt/spinner +if [ -f /TICI ] && [ ! -f _spinner ]; then + cp qt/spinner_larch64 _spinner fi -exec ./qt/spinner "$1" +exec ./_spinner "$1" diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index 622d198f7d..9ba9054ea1 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -2,30 +2,28 @@ import json import os import re -import shutil import unittest +import shutil +import tempfile import xml.etree.ElementTree as ET +import string +import requests +from parameterized import parameterized_class from openpilot.selfdrive.ui.update_translations import TRANSLATIONS_DIR, LANGUAGES_FILE, update_translations -TMP_TRANSLATIONS_DIR = os.path.join(TRANSLATIONS_DIR, "tmp") +with open(LANGUAGES_FILE, "r") as f: + translation_files = json.load(f) + UNFINISHED_TRANSLATION_TAG = "" not in cur_translations, - f"{file} ({name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them") + cur_translations = self._read_translation_file(TRANSLATIONS_DIR, self.file) + self.assertTrue("" not in cur_translations, + f"{self.file} ({self.name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them") def test_finished_translations(self): """ @@ -78,48 +66,68 @@ class TestTranslations(unittest.TestCase): - that translation is not empty - that translation format arguments are consistent """ - for name, file in self.translation_files.items(): - with self.subTest(name=name, file=file): - tr_xml = ET.parse(os.path.join(TRANSLATIONS_DIR, f"{file}.ts")) + tr_xml = ET.parse(os.path.join(TRANSLATIONS_DIR, f"{self.file}.ts")) - for context in tr_xml.getroot(): - for message in context.iterfind("message"): - translation = message.find("translation") - source_text = message.find("source").text + for context in tr_xml.getroot(): + for message in context.iterfind("message"): + translation = message.find("translation") + source_text = message.find("source").text - # Do not test unfinished translations - if translation.get("type") == "unfinished": - continue + # Do not test unfinished translations + if translation.get("type") == "unfinished": + continue - if message.get("numerus") == "yes": - numerusform = [t.text for t in translation.findall("numerusform")] + if message.get("numerus") == "yes": + numerusform = [t.text for t in translation.findall("numerusform")] - for nf in numerusform: - self.assertIsNotNone(nf, f"Ensure all plural translation forms are completed: {source_text}") - self.assertIn("%n", nf, "Ensure numerus argument (%n) exists in translation.") - self.assertIsNone(FORMAT_ARG.search(nf), "Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform)) + for nf in numerusform: + self.assertIsNotNone(nf, f"Ensure all plural translation forms are completed: {source_text}") + self.assertIn("%n", nf, "Ensure numerus argument (%n) exists in translation.") + self.assertIsNone(FORMAT_ARG.search(nf), "Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform)) - else: - self.assertIsNotNone(translation.text, f"Ensure translation is completed: {source_text}") + else: + self.assertIsNotNone(translation.text, f"Ensure translation is completed: {source_text}") - source_args = FORMAT_ARG.findall(source_text) - translation_args = FORMAT_ARG.findall(translation.text) - self.assertEqual(sorted(source_args), sorted(translation_args), - f"Ensure format arguments are consistent: `{source_text}` vs. `{translation.text}`") + source_args = FORMAT_ARG.findall(source_text) + translation_args = FORMAT_ARG.findall(translation.text) + self.assertEqual(sorted(source_args), sorted(translation_args), + f"Ensure format arguments are consistent: `{source_text}` vs. `{translation.text}`") def test_no_locations(self): - for name, file in self.translation_files.items(): - with self.subTest(name=name, file=file): - for line in self._read_translation_file(TRANSLATIONS_DIR, file).splitlines(): - self.assertFalse(line.strip().startswith(LOCATION_TAG), - f"Line contains location tag: {line.strip()}, remove all line numbers.") + for line in self._read_translation_file(TRANSLATIONS_DIR, self.file).splitlines(): + self.assertFalse(line.strip().startswith(LOCATION_TAG), + f"Line contains location tag: {line.strip()}, remove all line numbers.") def test_entities_error(self): - for name, file in self.translation_files.items(): - with self.subTest(name=name, file=file): - cur_translations = self._read_translation_file(TRANSLATIONS_DIR, file) - matches = re.findall(r'@(\w+);', cur_translations) - self.assertEqual(len(matches), 0, f"The string(s) {matches} were found with '@' instead of '&'") + cur_translations = self._read_translation_file(TRANSLATIONS_DIR, self.file) + matches = re.findall(r'@(\w+);', cur_translations) + self.assertEqual(len(matches), 0, f"The string(s) {matches} were found with '@' instead of '&'") + + def test_bad_language(self): + IGNORED_WORDS = {'pédale'} + + match = re.search(r'_([a-zA-Z]{2,3})', self.file) + assert match, f"{self.name} - could not parse language" + + response = requests.get(f"https://raw.githubusercontent.com/LDNOOBW/List-of-Dirty-Naughty-Obscene-and-Otherwise-Bad-Words/master/{match.group(1)}") + response.raise_for_status() + + banned_words = {line.strip() for line in response.text.splitlines()} + + for context in ET.parse(os.path.join(TRANSLATIONS_DIR, f"{self.file}.ts")).getroot(): + for message in context.iterfind("message"): + translation = message.find("translation") + if translation.get("type") == "unfinished": + continue + + translation_text = " ".join([t.text for t in translation.findall("numerusform")]) if message.get("numerus") == "yes" else translation.text + + if not translation_text: + continue + + words = set(translation_text.translate(str.maketrans('', '', string.punctuation + '%n')).lower().split()) + bad_words_found = words & (banned_words - IGNORED_WORDS) + assert not bad_words_found, f"Bad language found in {self.name}: '{translation_text}'. Bad word(s): {', '.join(bad_words_found)}" if __name__ == "__main__": diff --git a/selfdrive/ui/text b/selfdrive/ui/text index b44bec42bd..b12235f4e6 100755 --- a/selfdrive/ui/text +++ b/selfdrive/ui/text @@ -1,7 +1,7 @@ #!/bin/sh -if [ -f /TICI ] && [ ! -f qt/text ]; then - cp qt/text_larch64 qt/text +if [ -f /TICI ] && [ ! -f _text ]; then + cp qt/text_larch64 _text fi -exec ./qt/text "$1" +exec ./_text "$1" diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index 4159f28c31..eb6a580c01 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection منع تحميل البيانات الكبيرة عندما يكون الاتصال محدوداً + + Hidden Network + شبكة مخفية + + + CONNECT + الاتصال + + + Enter SSID + أدخل SSID + + + Enter password + أدخل كلمة المرور + + + for "%1" + من أجل "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting بدء تشغيل الكاميرا @@ -542,10 +562,6 @@ Exit إغلاق - - dashcam - dashcam - openpilot openpilot @@ -632,14 +648,14 @@ This may take up to a minute. يتم إعادة ضبط الجهاز... قد يستغرق الأمر حوالي الدقيقة. - - Press confirm to erase all content and settings. Press cancel to resume boot. - اضغط على تأكيد لمسح جميع المحتويات والإعدادات. اضغط على إلغاء لمتابعة التشغيل. - Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. غير قادر على تحميل جزء البيانات. قد يكون الجزء تالفاً. اضغط على تأكيد لمسح جهازك وإعادة ضبطه. + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + + SettingsWindow diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index e2e5771905..6d814b9625 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection Hochladen großer Dateien über getaktete Verbindungen unterbinden + + Hidden Network + + + + CONNECT + CONNECT + + + Enter SSID + SSID eingeben + + + Enter password + Passwort eingeben + + + for "%1" + für "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting Kamera startet @@ -537,10 +557,6 @@ Exit Verlassen - - dashcam - dashcam - openpilot openpilot @@ -614,12 +630,12 @@ - Press confirm to erase all content and settings. Press cancel to resume boot. + Resetting device... +This may take up to a minute. - Resetting device... -This may take up to a minute. + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index 456efe6366..cd96c466e9 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection Éviter les transferts de données importants sur une connexion limitée + + Hidden Network + Réseau Caché + + + CONNECT + CONNECTER + + + Enter SSID + Entrer le SSID + + + Enter password + Entrer le mot de passe + + + for "%1" + pour "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting démarrage de la caméra @@ -538,10 +558,6 @@ Exit Quitter - - dashcam - dashcam - openpilot openpilot @@ -604,10 +620,6 @@ Cela peut prendre jusqu'à une minute. System Reset Réinitialisation du système - - Press confirm to erase all content and settings. Press cancel to resume boot. - Appuyez sur confirmer pour effacer tout le contenu et les paramètres. Appuyez sur annuler pour reprendre le démarrage. - Cancel Annuler @@ -624,6 +636,10 @@ Cela peut prendre jusqu'à une minute. Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. Impossible de monter la partition data. La partition peut être corrompue. Appuyez sur confirmer pour effacer et réinitialiser votre appareil. + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + + SettingsWindow diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 63de8f0471..d07c7d525a 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection 大量のデータのアップロードを防止します。 + + Hidden Network + + + + CONNECT + 接続 + + + Enter SSID + SSID を入力 + + + Enter password + パスワードを入力 + + + for "%1" + ネットワーク名:%1 + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting カメラを起動しています @@ -536,10 +556,6 @@ Exit 閉じる - - dashcam - ドライブレコーダー - openpilot openpilot @@ -610,12 +626,12 @@ - Press confirm to erase all content and settings. Press cancel to resume boot. + Resetting device... +This may take up to a minute. - Resetting device... -This may take up to a minute. + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index bc0c5f2b0e..a903978329 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection 데이터 요금제 연결 시 대용량 데이터 업로드를 방지합니다 + + Hidden Network + 숨겨진 네트워크 + + + CONNECT + 연결됨 + + + Enter SSID + SSID 입력 + + + Enter password + 비밀번호를 입력하세요 + + + for "%1" + "%1"에 접속하려면 비밀번호가 필요합니다 + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting 카메라 시작 중 @@ -537,10 +557,6 @@ Exit 종료 - - dashcam - 블랙박스 - openpilot openpilot @@ -610,16 +626,16 @@ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. 데이터 파티션을 마운트할 수 없습니다. 파티션이 손상되었을 수 있습니다. 모든 설정을 삭제하고 장치를 초기화하려면 확인을 누르세요. - - Press confirm to erase all content and settings. Press cancel to resume boot. - 모든 콘텐츠와 설정을 삭제하려면 확인을 누르세요. 계속 부팅하려면 취소를 누르세요. - Resetting device... This may take up to a minute. 장치를 초기화하는 중... 최대 1분이 소요될 수 있습니다. + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + + SettingsWindow diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 4cf37cc585..fce5a8a8ff 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection Evite grandes uploads de dados quando estiver em uma conexão limitada + + Hidden Network + Rede Oculta + + + CONNECT + CONECTE + + + Enter SSID + Digite o SSID + + + Enter password + Insira a senha + + + for "%1" + para "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting câmera iniciando @@ -538,10 +558,6 @@ Exit Sair - - dashcam - dashcam - openpilot openpilot @@ -614,16 +630,16 @@ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. Não é possível montar a partição de dados. Partição corrompida. Confirme para apagar e redefinir o dispositivo. - - Press confirm to erase all content and settings. Press cancel to resume boot. - Pressione confirmar para apagar todo o conteúdo e configurações. Pressione cancelar para voltar. - Resetting device... This may take up to a minute. Redefinindo o dispositivo Isso pode levar até um minuto. + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + Reinicialização do sistema acionada. Pressione confirmar para apagar todo o conteúdo e configurações. Pressione cancel para retomar a inicialização. + SettingsWindow diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index a1748a6951..f4d097b2a2 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection ปิดการอัพโหลดข้อมูลขนาดใหญ่เมื่อเชื่อมต่อผ่านเซลลูล่าร์ + + Hidden Network + + + + CONNECT + เชื่อมต่อ + + + Enter SSID + ป้อนค่า SSID + + + Enter password + ใส่รหัสผ่าน + + + for "%1" + สำหรับ "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting กำลังเปิดกล้อง @@ -537,10 +557,6 @@ Exit ปิด - - dashcam - กล้องติดรถยนต์ - openpilot openpilot @@ -612,14 +628,14 @@ This may take up to a minute. กำลังรีเซ็ตอุปกรณ์... อาจใช้เวลาถึงหนึ่งนาที - - Press confirm to erase all content and settings. Press cancel to resume boot. - กดยืนยันเพื่อลบข้อมูลและการตั้งค่าทั้งหมด กดยกเลิกเพื่อบูตต่อ - Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. ไม่สามารถเมานต์พาร์ติชั่นข้อมูลได้ พาร์ติชั่นอาจเสียหาย กดยืนยันเพื่อลบและรีเซ็ตอุปกรณ์ของคุณ + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + + SettingsWindow diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index 51fdddd5ce..ec6f71f5b0 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection + + Hidden Network + + + + CONNECT + BAĞLANTI + + + Enter SSID + APN Gir + + + Enter password + Parolayı girin + + + for "%1" + için "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting kamera başlatılıyor @@ -536,10 +556,6 @@ Exit Çık - - dashcam - araç yol kamerası - openpilot openpilot @@ -611,11 +627,11 @@ This may take up to a minute. - Press confirm to erase all content and settings. Press cancel to resume boot. + Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. - Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 7b682535ce..91f55c6e94 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection 当使用按流量计费的连接时,避免上传大流量数据 + + Hidden Network + + + + CONNECT + CONNECT + + + Enter SSID + 输入SSID + + + Enter password + 输入密码 + + + for "%1" + 网络名称:"%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting 正在启动相机 @@ -537,10 +557,6 @@ Exit 退出 - - dashcam - 行车记录仪 - openpilot openpilot @@ -610,16 +626,16 @@ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. 无法挂载数据分区。分区可能已经损坏。请确认是否要删除并重新设置。 - - Press confirm to erase all content and settings. Press cancel to resume boot. - 按下确认以删除所有内容及设置。按下取消来继续开机。 - Resetting device... This may take up to a minute. 设备重置中… 这可能需要一分钟的时间。 + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + + SettingsWindow diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 1794cc78ac..e8c8854d0e 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -66,6 +66,26 @@ Prevent large data uploads when on a metered connection 防止使用行動網路上傳大量的數據 + + Hidden Network + + + + CONNECT + 雲端服務 + + + Enter SSID + 輸入 SSID + + + Enter password + 輸入密碼 + + + for "%1" + 給 "%1" + AnnotatedCameraWidget @@ -275,7 +295,7 @@ - DriverViewScene + DriverViewWindow camera starting 開啟相機中 @@ -537,10 +557,6 @@ Exit 離開 - - dashcam - 行車記錄器 - openpilot openpilot @@ -610,16 +626,16 @@ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. 無法掛載資料分割區。分割區可能已經毀損。請確認是否要刪除並重新設定。 - - Press confirm to erase all content and settings. Press cancel to resume boot. - 按下確認以刪除所有內容及設定。按下取消來繼續開機。 - Resetting device... This may take up to a minute. 設備重設中… 這可能需要一分鐘的時間。 + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + + SettingsWindow diff --git a/selfdrive/ui/ui b/selfdrive/ui/ui deleted file mode 100755 index acb2a705a8..0000000000 --- a/selfdrive/ui/ui +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/sh -cd "$(dirname "$0")" -export QT_DBL_CLICK_DIST=150 -exec ./_ui diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 03df2cf57a..9afd22f13a 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -38,7 +38,7 @@ static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height) { const auto line_x = line.getX(); int max_idx = 0; - for (int i = 1; i < TRAJECTORY_SIZE && line_x[i] <= path_height; ++i) { + for (int i = 1; i < line_x.size() && line_x[i] <= path_height; ++i) { max_idx = i; } return max_idx; @@ -84,10 +84,10 @@ void update_model(UIState *s, const cereal::UiPlan::Reader &plan) { UIScene &scene = s->scene; auto plan_position = plan.getPosition(); - if (plan_position.getX().size() < TRAJECTORY_SIZE){ + if (plan_position.getX().size() < model.getPosition().getX().size()) { plan_position = model.getPosition(); } - float max_distance = std::clamp(plan_position.getX()[TRAJECTORY_SIZE - 1], + float max_distance = std::clamp(*(plan_position.getX().end() - 1), MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); // update lane lines @@ -207,6 +207,12 @@ static void update_state(UIState *s) { scene.light_sensor = std::max(100.0f - scale * cam_state.getExposureValPercent(), 0.0f); } scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; + + scene.world_objects_visible = scene.world_objects_visible || + (scene.started && + sm.rcv_frame("liveCalibration") > scene.started_frame && + sm.rcv_frame("modelV2") > scene.started_frame && + sm.rcv_frame("uiPlan") > scene.started_frame); } void ui_update_params(UIState *s) { @@ -233,13 +239,14 @@ void UIState::updateStatus() { scene.started_frame = sm->frame; } started_prev = scene.started; + scene.world_objects_visible = false; emit offroadTransition(!scene.started); } } UIState::UIState(QObject *parent) : QObject(parent) { sm = std::make_unique>({ - "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", + "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2", "wideRoadCameraState", "managerState", "navInstruction", "navRoute", "uiPlan", }); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index dc180eebfb..86cd70f028 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -3,7 +3,6 @@ #include #include #include -#include #include #include @@ -13,9 +12,10 @@ #include #include "cereal/messaging/messaging.h" -#include "common/modeldata.h" +#include "common/mat.h" #include "common/params.h" #include "common/timing.h" +#include "system/hardware/hw.h" const int UI_BORDER_SIZE = 30; const int UI_HEADER_HEIGHT = 420; @@ -24,7 +24,18 @@ const int UI_FREQ = 20; // Hz const int BACKLIGHT_OFFROAD = 50; typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; -const mat3 DEFAULT_CALIBRATION = {{ 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0 }}; +const float MIN_DRAW_DISTANCE = 10.0; +const float MAX_DRAW_DISTANCE = 100.0; +constexpr mat3 DEFAULT_CALIBRATION = {{ 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0 }}; +constexpr mat3 FCAM_INTRINSIC_MATRIX = (mat3){{2648.0, 0.0, 1928.0 / 2, + 0.0, 2648.0, 1208.0 / 2, + 0.0, 0.0, 1.0}}; +// tici ecam focal probably wrong? magnification is not consistent across frame +// Need to retrain model before this can be changed +constexpr mat3 ECAM_INTRINSIC_MATRIX = (mat3){{567.0, 0.0, 1928.0 / 2, + 0.0, 567.0, 1208.0 / 2, + 0.0, 0.0, 1.0}}; + constexpr vec3 default_face_kpts_3d[] = { {-5.98, -51.20, 8.00}, {-17.64, -49.14, 8.00}, {-23.81, -46.40, 8.00}, {-29.98, -40.91, 8.00}, {-32.04, -37.49, 8.00}, @@ -147,6 +158,7 @@ typedef struct UIScene { float light_sensor; bool started, ignition, is_metric, map_on_left, longitudinal_control; + bool world_objects_visible = false; uint64_t started_frame; } UIScene; @@ -156,9 +168,6 @@ class UIState : public QObject { public: UIState(QObject* parent = 0); void updateStatus(); - inline bool worldObjectsVisible() const { - return sm->rcv_frame("liveCalibration") > scene.started_frame; - } inline bool engaged() const { return scene.started && (*sm)["controlsState"].getControlsState().getEnabled(); } diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index 004c6425dc..e988a13b7f 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -9,6 +9,7 @@ UI_DIR = os.path.join(BASEDIR, "selfdrive", "ui") TRANSLATIONS_DIR = os.path.join(UI_DIR, "translations") LANGUAGES_FILE = os.path.join(TRANSLATIONS_DIR, "languages.json") TRANSLATIONS_INCLUDE_FILE = os.path.join(TRANSLATIONS_DIR, "alerts_generated.h") +PLURAL_ONLY = ["main_en"] # base language, only create entries for strings with plural forms def generate_translations_include(): @@ -22,21 +23,20 @@ def generate_translations_include(): with open(TRANSLATIONS_INCLUDE_FILE, "w") as f: f.write(content) -def update_translations(vanish=False, plural_only=None, translations_dir=TRANSLATIONS_DIR): - generate_translations_include() - if plural_only is None: - plural_only = [] +def update_translations(vanish: bool = False, translation_files: None | list[str] = None, translations_dir: str = TRANSLATIONS_DIR): + generate_translations_include() - with open(LANGUAGES_FILE, "r") as f: - translation_files = json.load(f) + if translation_files is None: + with open(LANGUAGES_FILE, "r") as f: + translation_files = json.load(f).values() - for file in translation_files.values(): + for file in translation_files: tr_file = os.path.join(translations_dir, f"{file}.ts") args = f"lupdate -locations none -recursive {UI_DIR} -ts {tr_file} -I {BASEDIR}" if vanish: args += " -no-obsolete" - if file in plural_only: + if file in PLURAL_ONLY: args += " -pluralonly" ret = os.system(args) assert ret == 0 @@ -46,8 +46,6 @@ if __name__ == "__main__": parser = argparse.ArgumentParser(description="Update translation files for UI", formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument("--vanish", action="store_true", help="Remove translations with source text no longer found") - parser.add_argument("--plural-only", type=str, nargs="*", default=["main_en"], - help="Translation codes to only create plural translations for (ie. the base language)") args = parser.parse_args() - update_translations(args.vanish, args.plural_only) + update_translations(args.vanish) diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 1e128fb11c..3e4a849d21 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -18,7 +18,7 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params from openpilot.common.time import system_time_valid from openpilot.system.hardware import AGNOS, HARDWARE -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert from openpilot.system.version import is_tested_branch @@ -35,26 +35,42 @@ OVERLAY_INIT = Path(os.path.join(BASEDIR, ".overlay_init")) DAYS_NO_CONNECTIVITY_MAX = 14 # do not allow to engage after this many days DAYS_NO_CONNECTIVITY_PROMPT = 10 # send an offroad prompt after this many days +class UserRequest: + NONE = 0 + CHECK = 1 + FETCH = 2 + class WaitTimeHelper: def __init__(self): self.ready_event = threading.Event() - self.only_check_for_update = False + self.user_request = UserRequest.NONE signal.signal(signal.SIGHUP, self.update_now) signal.signal(signal.SIGUSR1, self.check_now) def update_now(self, signum: int, frame) -> None: cloudlog.info("caught SIGHUP, attempting to downloading update") - self.only_check_for_update = False + self.user_request = UserRequest.FETCH self.ready_event.set() def check_now(self, signum: int, frame) -> None: cloudlog.info("caught SIGUSR1, checking for updates") - self.only_check_for_update = True + self.user_request = UserRequest.CHECK self.ready_event.set() def sleep(self, t: float) -> None: self.ready_event.wait(timeout=t) +def write_time_to_param(params, param) -> None: + t = datetime.datetime.utcnow() + params.put(param, t.isoformat().encode('utf8')) + +def read_time_from_param(params, param) -> Optional[datetime.datetime]: + t = params.get(param, encoding='utf8') + try: + return datetime.datetime.fromisoformat(t) + except (TypeError, ValueError): + pass + return None def run(cmd: List[str], cwd: Optional[str] = None) -> str: return subprocess.check_output(cmd, cwd=cwd, stderr=subprocess.STDOUT, encoding='utf8') @@ -230,7 +246,6 @@ class Updater: b: Union[str, None] = self.params.get("UpdaterTargetBranch", encoding='utf-8') if b is None: b = self.get_branch(BASEDIR) - self.params.put("UpdaterTargetBranch", b) return b @property @@ -245,7 +260,7 @@ class Updater: @property def update_available(self) -> bool: - if os.path.isdir(OVERLAY_MERGED): + if os.path.isdir(OVERLAY_MERGED) and len(self.branches) > 0: hash_mismatch = self.get_commit_hash(OVERLAY_MERGED) != self.branches[self.target_branch] branch_mismatch = self.get_branch(OVERLAY_MERGED) != self.target_branch return hash_mismatch or branch_mismatch @@ -259,20 +274,19 @@ class Updater: def set_params(self, update_success: bool, failed_count: int, exception: Optional[str]) -> None: self.params.put("UpdateFailedCount", str(failed_count)) + self.params.put("UpdaterTargetBranch", self.target_branch) self.params.put_bool("UpdaterFetchAvailable", self.update_available) - self.params.put("UpdaterAvailableBranches", ','.join(self.branches.keys())) + if len(self.branches): + self.params.put("UpdaterAvailableBranches", ','.join(self.branches.keys())) last_update = datetime.datetime.utcnow() if update_success: - t = last_update.isoformat() - self.params.put("LastUpdateTime", t.encode('utf8')) + write_time_to_param(self.params, "LastUpdateTime") else: - try: - t = self.params.get("LastUpdateTime", encoding='utf8') - last_update = datetime.datetime.fromisoformat(t) - except (TypeError, ValueError): - pass + t = read_time_from_param(self.params, "LastUpdateTime") + if t is not None: + last_update = t if exception is None: self.params.remove("LastUpdateException") @@ -328,7 +342,7 @@ class Updater: def check_for_update(self) -> None: cloudlog.info("checking for updates") - excluded_branches = ('release2', 'release2-staging', 'dashcam', 'dashcam-staging') + excluded_branches = ('release2', 'release2-staging') try: run(["git", "ls-remote", "origin", "HEAD"], OVERLAY_MERGED) @@ -399,88 +413,96 @@ def main() -> None: cloudlog.warning("updates are disabled by the DisableUpdates param") exit(0) - ov_lock_fd = open(LOCK_FILE, 'w') - try: - fcntl.flock(ov_lock_fd, fcntl.LOCK_EX | fcntl.LOCK_NB) - except OSError as e: - raise RuntimeError("couldn't get overlay lock; is another instance running?") from e - - # Set low io priority - proc = psutil.Process() - if psutil.LINUX: - proc.ionice(psutil.IOPRIO_CLASS_BE, value=7) - - # Check if we just performed an update - if Path(os.path.join(STAGING_ROOT, "old_openpilot")).is_dir(): - cloudlog.event("update installed") - - if not params.get("InstallDate"): - t = datetime.datetime.utcnow().isoformat() - params.put("InstallDate", t.encode('utf8')) - - updater = Updater() - update_failed_count = 0 # TODO: Load from param? - - # no fetch on the first time - wait_helper = WaitTimeHelper() - wait_helper.only_check_for_update = True + with open(LOCK_FILE, 'w') as ov_lock_fd: + try: + fcntl.flock(ov_lock_fd, fcntl.LOCK_EX | fcntl.LOCK_NB) + except OSError as e: + raise RuntimeError("couldn't get overlay lock; is another instance running?") from e - # invalidate old finalized update - set_consistent_flag(False) + # Set low io priority + proc = psutil.Process() + if psutil.LINUX: + proc.ionice(psutil.IOPRIO_CLASS_BE, value=7) - # Run the update loop - while True: - wait_helper.ready_event.clear() + # Check if we just performed an update + if Path(os.path.join(STAGING_ROOT, "old_openpilot")).is_dir(): + cloudlog.event("update installed") - # Attempt an update - exception = None - try: - # TODO: reuse overlay from previous updated instance if it looks clean - init_overlay() + if not params.get("InstallDate"): + t = datetime.datetime.utcnow().isoformat() + params.put("InstallDate", t.encode('utf8')) - # ensure we have some params written soon after startup - updater.set_params(False, update_failed_count, exception) + updater = Updater() + update_failed_count = 0 # TODO: Load from param? + wait_helper = WaitTimeHelper() - if not system_time_valid(): - wait_helper.sleep(60) - continue + # invalidate old finalized update + set_consistent_flag(False) - update_failed_count += 1 + # set initial state + params.put("UpdaterState", "idle") - # check for update - params.put("UpdaterState", "checking...") - updater.check_for_update() + # Run the update loop + first_run = True + while True: + wait_helper.ready_event.clear() - # download update - if wait_helper.only_check_for_update: - cloudlog.info("skipping fetch this cycle") - else: - updater.fetch_update() - update_failed_count = 0 - except subprocess.CalledProcessError as e: - cloudlog.event( - "update process failed", - cmd=e.cmd, - output=e.output, - returncode=e.returncode - ) - exception = f"command failed: {e.cmd}\n{e.output}" - OVERLAY_INIT.unlink(missing_ok=True) - except Exception as e: - cloudlog.exception("uncaught updated exception, shouldn't happen") - exception = str(e) - OVERLAY_INIT.unlink(missing_ok=True) + # Attempt an update + exception = None + try: + # TODO: reuse overlay from previous updated instance if it looks clean + init_overlay() + + # ensure we have some params written soon after startup + updater.set_params(False, update_failed_count, exception) + + if not system_time_valid() or first_run: + first_run = False + wait_helper.sleep(60) + continue + + update_failed_count += 1 + + # check for update + params.put("UpdaterState", "checking...") + updater.check_for_update() + + # download update + last_fetch = read_time_from_param(params, "UpdaterLastFetchTime") + timed_out = last_fetch is None or (datetime.datetime.utcnow() - last_fetch > datetime.timedelta(days=3)) + user_requested_fetch = wait_helper.user_request == UserRequest.FETCH + if params.get_bool("NetworkMetered") and not timed_out and not user_requested_fetch: + cloudlog.info("skipping fetch, connection metered") + elif wait_helper.user_request == UserRequest.CHECK: + cloudlog.info("skipping fetch, only checking") + else: + updater.fetch_update() + write_time_to_param(params, "UpdaterLastFetchTime") + update_failed_count = 0 + except subprocess.CalledProcessError as e: + cloudlog.event( + "update process failed", + cmd=e.cmd, + output=e.output, + returncode=e.returncode + ) + exception = f"command failed: {e.cmd}\n{e.output}" + OVERLAY_INIT.unlink(missing_ok=True) + except Exception as e: + cloudlog.exception("uncaught updated exception, shouldn't happen") + exception = str(e) + OVERLAY_INIT.unlink(missing_ok=True) - try: - params.put("UpdaterState", "idle") - update_successful = (update_failed_count == 0) - updater.set_params(update_successful, update_failed_count, exception) - except Exception: - cloudlog.exception("uncaught updated exception while setting params, shouldn't happen") + try: + params.put("UpdaterState", "idle") + update_successful = (update_failed_count == 0) + updater.set_params(update_successful, update_failed_count, exception) + except Exception: + cloudlog.exception("uncaught updated exception while setting params, shouldn't happen") - # infrequent attempts if we successfully updated recently - wait_helper.only_check_for_update = False - wait_helper.sleep(5*60 if update_failed_count > 0 else 1.5*60*60) + # infrequent attempts if we successfully updated recently + wait_helper.user_request = UserRequest.NONE + wait_helper.sleep(5*60 if update_failed_count > 0 else 1.5*60*60) if __name__ == "__main__": diff --git a/system/camerad/SConscript b/system/camerad/SConscript index ffd7278bbb..8f19e7ee19 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -2,13 +2,9 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic'] -camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc']) -env.Program('camerad', [ - 'main.cc', - camera_obj, - ], LIBS=libs) +camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc', + 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) +env.Program('camerad', ['main.cc', camera_obj], LIBS=libs) if GetOption("extras") and arch == "x86_64": - env.Program('test/ae_gray_test', - ['test/ae_gray_test.cc', camera_obj], - LIBS=libs) + env.Program('test/test_ae_gray', ['test/test_ae_gray.cc', camera_obj], LIBS=libs) diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc index 23b28357da..91c6d44f84 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -1,22 +1,14 @@ #include "system/camerad/cameras/camera_common.h" -#include - #include -#include -#include #include -#include #include "third_party/libyuv/include/libyuv.h" #include -#include "system/camerad/imgproc/utils.h" #include "common/clutil.h" -#include "common/modeldata.h" #include "common/swaglog.h" #include "common/util.h" -#include "system/hardware/hw.h" #include "third_party/linux/include/msm_media_info.h" #include "system/camerad/cameras/camera_qcom2.h" @@ -30,15 +22,15 @@ class Debayer { public: Debayer(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s, int buf_width, int uv_offset) { char args[4096]; - const CameraInfo *ci = &s->ci; + const SensorInfo *ci = s->ci.get(); snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " - "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " + "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " "-DIS_OX=%d -DCAM_NUM=%d%s", ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset, - b->rgb_width, b->rgb_height, b->rgb_stride, buf_width, uv_offset, - s->camera_id==CAMERA_ID_OX03C10 ? 1 : 0, s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : ""); + b->rgb_width, b->rgb_height, buf_width, uv_offset, + ci->image_sensor == cereal::FrameData::ImageSensor::OX03C10, s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : ""); const char *cl_file = "cameras/real_debayer.cl"; cl_program prg_debayer = cl_program_from_file(context, device_id, cl_file, args); krnl_ = CL_CHECK_ERR(clCreateKernel(prg_debayer, "debayer10", &err)); @@ -63,12 +55,12 @@ private: cl_kernel krnl_; }; -void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType init_yuv_type) { +void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type) { vipc_server = v; - this->yuv_type = init_yuv_type; + stream_type = type; frame_buf_count = frame_cnt; - const CameraInfo *ci = &s->ci; + const SensorInfo *ci = s->ci.get(); // RAW frame const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride; camera_bufs = std::make_unique(frame_buf_count); @@ -89,17 +81,13 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, assert(nv12_height/2 == VENUS_UV_SCANLINES(COLOR_FMT_NV12, rgb_height)); size_t nv12_size = 2346 * nv12_width; // comes from v4l2_format.fmt.pix_mp.plane_fmt[0].sizeimage size_t nv12_uv_offset = nv12_width * nv12_height; - vipc_server->create_buffers_with_sizes(yuv_type, YUV_BUFFER_COUNT, false, rgb_width, rgb_height, nv12_size, nv12_width, nv12_uv_offset); + vipc_server->create_buffers_with_sizes(stream_type, YUV_BUFFER_COUNT, false, rgb_width, rgb_height, nv12_size, nv12_width, nv12_uv_offset); LOGD("created %d YUV vipc buffers with size %dx%d", YUV_BUFFER_COUNT, nv12_width, nv12_height); debayer = new Debayer(device_id, context, this, s, nv12_width, nv12_uv_offset); -#ifdef __APPLE__ - q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err)); -#else const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; q = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err)); -#endif } CameraBuf::~CameraBuf() { @@ -119,7 +107,7 @@ bool CameraBuf::acquire() { } cur_frame_data = camera_bufs_metadata[cur_buf_idx]; - cur_yuv_buf = vipc_server->get_buffer(yuv_type); + cur_yuv_buf = vipc_server->get_buffer(stream_type); cur_camera_buf = &camera_bufs[cur_buf_idx]; double start_time = millis_since_boot(); @@ -148,6 +136,7 @@ void CameraBuf::queue(size_t buf_idx) { void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c) { framed.setFrameId(frame_data.frame_id); + framed.setRequestId(frame_data.request_id); framed.setTimestampEof(frame_data.timestamp_eof); framed.setTimestampSof(frame_data.timestamp_sof); framed.setIntegLines(frame_data.integ_lines); @@ -158,14 +147,9 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr framed.setProcessingTime(frame_data.processing_time); const float ev = c->cur_ev[frame_data.frame_id % 3]; - const float perc = util::map_val(ev, c->min_ev, c->max_ev, 0.0f, 100.0f); + const float perc = util::map_val(ev, c->ci->min_ev, c->ci->max_ev, 0.0f, 100.0f); framed.setExposureValPercent(perc); - - if (c->camera_id == CAMERA_ID_AR0231) { - framed.setSensor(cereal::FrameData::ImageSensor::AR0231); - } else if (c->camera_id == CAMERA_ID_OX03C10) { - framed.setSensor(cereal::FrameData::ImageSensor::OX03C10); - } + framed.setSensor(c->ci->image_sensor); } kj::Array get_raw_frame_image(const CameraBuf *b) { @@ -282,7 +266,6 @@ float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip } } - // Find mean lumimance value unsigned int lum_cur = 0; for (lum_med = 255; lum_med >= 0; lum_med--) { diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 0f69aa3774..f98691ef00 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -1,30 +1,12 @@ #pragma once -#include -#include +#include #include #include #include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionbuf.h" -#include "cereal/visionipc/visionipc.h" #include "cereal/visionipc/visionipc_server.h" -#include "common/mat.h" #include "common/queue.h" -#include "common/swaglog.h" -#include "system/hardware/hw.h" - -#define CAMERA_ID_IMX298 0 -#define CAMERA_ID_IMX179 1 -#define CAMERA_ID_S5K3P8SP 2 -#define CAMERA_ID_OV8865 3 -#define CAMERA_ID_IMX298_FLIPPED 4 -#define CAMERA_ID_OV10640 5 -#define CAMERA_ID_LGC920 6 -#define CAMERA_ID_LGC615 7 -#define CAMERA_ID_AR0231 8 -#define CAMERA_ID_OX03C10 9 -#define CAMERA_ID_MAX 10 const int YUV_BUFFER_COUNT = 20; @@ -42,20 +24,12 @@ const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != NULL; -typedef struct CameraInfo { - uint32_t frame_width, frame_height; - uint32_t frame_stride; - uint32_t frame_offset = 0; - uint32_t extra_height = 0; - int registers_offset = -1; - int stats_offset = -1; -} CameraInfo; - typedef struct FrameMetadata { uint32_t frame_id; + uint32_t request_id; // Timestamps - uint64_t timestamp_sof; // only set on tici + uint64_t timestamp_sof; uint64_t timestamp_eof; // Exposure @@ -76,7 +50,7 @@ class CameraBuf { private: VisionIpcServer *vipc_server; Debayer *debayer = nullptr; - VisionStreamType yuv_type; + VisionStreamType stream_type; int cur_buf_idx; SafeQueue safe_queue; int frame_buf_count; @@ -88,11 +62,11 @@ public: VisionBuf *cur_camera_buf; std::unique_ptr camera_bufs; std::unique_ptr camera_bufs_metadata; - int rgb_width, rgb_height, rgb_stride; + int rgb_width, rgb_height; CameraBuf() = default; ~CameraBuf(); - void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType yuv_type); + void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type); bool acquire(); void queue(size_t buf_idx); }; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 3a9ecb467b..3191b821ac 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1,17 +1,12 @@ #include "system/camerad/cameras/camera_qcom2.h" -#include #include #include -#include -#include #include -#include #include #include #include -#include #include #include #include @@ -19,105 +14,18 @@ #include "media/cam_defs.h" #include "media/cam_isp.h" #include "media/cam_isp_ife.h" -#include "media/cam_sensor.h" +#include "media/cam_req_mgr.h" #include "media/cam_sensor_cmn_header.h" #include "media/cam_sync.h" #include "common/swaglog.h" -#include "system/camerad/cameras/sensor2_i2c.h" + +const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py // For debugging: // echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl extern ExitHandler do_exit; -const size_t FRAME_WIDTH = 1928; -const size_t FRAME_HEIGHT = 1208; -const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) - -const size_t AR0231_REGISTERS_HEIGHT = 2; -// TODO: this extra height is universal and doesn't apply per camera -const size_t AR0231_STATS_HEIGHT = 2+8; - -const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py - -CameraInfo cameras_supported[CAMERA_ID_MAX] = { - [CAMERA_ID_AR0231] = { - .frame_width = FRAME_WIDTH, - .frame_height = FRAME_HEIGHT, - .frame_stride = FRAME_STRIDE, - .extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT, - - .registers_offset = 0, - .frame_offset = AR0231_REGISTERS_HEIGHT, - .stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT, - }, - [CAMERA_ID_OX03C10] = { - .frame_width = FRAME_WIDTH, - .frame_height = FRAME_HEIGHT, - .frame_stride = FRAME_STRIDE, // (0xa80*12//8) - .extra_height = 16, // top 2 + bot 14 - .frame_offset = 2, - }, -}; - -const float DC_GAIN_AR0231 = 2.5; -const float DC_GAIN_OX03C10 = 7.32; - -const float DC_GAIN_ON_GREY_AR0231 = 0.2; -const float DC_GAIN_OFF_GREY_AR0231 = 0.3; -const float DC_GAIN_ON_GREY_OX03C10 = 0.9; -const float DC_GAIN_OFF_GREY_OX03C10 = 1.0; - -const int DC_GAIN_MIN_WEIGHT_AR0231 = 0; -const int DC_GAIN_MAX_WEIGHT_AR0231 = 1; -const int DC_GAIN_MIN_WEIGHT_OX03C10 = 1; // always on is fine -const int DC_GAIN_MAX_WEIGHT_OX03C10 = 1; - -const float TARGET_GREY_FACTOR_AR0231 = 1.0; -const float TARGET_GREY_FACTOR_OX03C10 = 0.01; - -const float sensor_analog_gains_AR0231[] = { - 1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3 - 3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7 - 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11 - 7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass - -const float sensor_analog_gains_OX03C10[] = { - 1.0, 1.0625, 1.125, 1.1875, 1.25, 1.3125, 1.375, 1.4375, 1.5, 1.5625, 1.6875, - 1.8125, 1.9375, 2.0, 2.125, 2.25, 2.375, 2.5, 2.625, 2.75, 2.875, 3.0, - 3.125, 3.375, 3.625, 3.875, 4.0, 4.25, 4.5, 4.75, 5.0, 5.25, 5.5, - 5.75, 6.0, 6.25, 6.5, 7.0, 7.5, 8.0, 8.5, 9.0, 9.5, 10.0, - 10.5, 11.0, 11.5, 12.0, 12.5, 13.0, 13.5, 14.0, 14.5, 15.0, 15.5}; - -const uint32_t ox03c10_analog_gains_reg[] = { - 0x100, 0x110, 0x120, 0x130, 0x140, 0x150, 0x160, 0x170, 0x180, 0x190, 0x1B0, - 0x1D0, 0x1F0, 0x200, 0x220, 0x240, 0x260, 0x280, 0x2A0, 0x2C0, 0x2E0, 0x300, - 0x320, 0x360, 0x3A0, 0x3E0, 0x400, 0x440, 0x480, 0x4C0, 0x500, 0x540, 0x580, - 0x5C0, 0x600, 0x640, 0x680, 0x700, 0x780, 0x800, 0x880, 0x900, 0x980, 0xA00, - 0xA80, 0xB00, 0xB80, 0xC00, 0xC80, 0xD00, 0xD80, 0xE00, 0xE80, 0xF00, 0xF80}; - -const int ANALOG_GAIN_MIN_IDX_AR0231 = 0x1; // 0.25x -const int ANALOG_GAIN_REC_IDX_AR0231 = 0x6; // 0.8x -const int ANALOG_GAIN_MAX_IDX_AR0231 = 0xD; // 4.0x -const int ANALOG_GAIN_COST_DELTA_AR0231 = 0; -const float ANALOG_GAIN_COST_LOW_AR0231 = 0.1; -const float ANALOG_GAIN_COST_HIGH_AR0231 = 5.0; - -const int ANALOG_GAIN_MIN_IDX_OX03C10 = 0x0; -const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x0; // 1x -const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0x36; -const int ANALOG_GAIN_COST_DELTA_OX03C10 = -1; -const float ANALOG_GAIN_COST_LOW_OX03C10 = 0.4; -const float ANALOG_GAIN_COST_HIGH_OX03C10 = 6.4; - -const int EXPOSURE_TIME_MIN_AR0231 = 2; // with HDR, fastest ss -const int EXPOSURE_TIME_MAX_AR0231 = 0x0855; // with HDR, slowest ss, 40ms - -const int EXPOSURE_TIME_MIN_OX03C10 = 2; // 1x -const int EXPOSURE_TIME_MAX_OX03C10 = 2016; -const uint32_t VS_TIME_MIN_OX03C10 = 1; -const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 - int CameraState::clear_req_queue() { struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; req_mgr_flush_request.session_hdl = session_handle; @@ -134,13 +42,7 @@ int CameraState::clear_req_queue() { void CameraState::sensors_start() { if (!enabled) return; LOGD("starting sensor %d", camera_num); - if (camera_id == CAMERA_ID_AR0231) { - sensors_i2c(start_reg_array_ar0231, std::size(start_reg_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); - } else if (camera_id == CAMERA_ID_OX03C10) { - sensors_i2c(start_reg_array_ox03c10, std::size(start_reg_array_ox03c10), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); - } else { - assert(false); - } + sensors_i2c(ci->start_reg_array.data(), ci->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); } void CameraState::sensors_poke(int request_id) { @@ -161,7 +63,7 @@ void CameraState::sensors_poke(int request_id) { } } -void CameraState::sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) { +void CameraState::sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) { // LOGD("sensors_i2c: %d", len); uint32_t cam_packet_handle = 0; int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; @@ -215,21 +117,7 @@ int CameraState::sensors_init() { auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); probe->camera_id = camera_num; - switch (camera_num) { - case 0: - // port 0 - i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x6C; // 6C = 0x36*2 - break; - case 1: - // port 1 - i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x30 : 0x20; - break; - case 2: - // port 2 - i2c_info->slave_addr = (camera_id == CAMERA_ID_AR0231) ? 0x20 : 0x6C; - break; - } - + i2c_info->slave_addr = ci->getSlaveAddress(camera_num); // 0(I2C_STANDARD_MODE) = 100khz, 1(I2C_FAST_MODE) = 400khz //i2c_info->i2c_freq_mode = I2C_STANDARD_MODE; i2c_info->i2c_freq_mode = I2C_FAST_MODE; @@ -239,22 +127,14 @@ int CameraState::sensors_init() { probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; probe->op_code = 3; // don't care? probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; - if (camera_id == CAMERA_ID_AR0231) { - probe->reg_addr = 0x3000; - probe->expected_data = 0x354; - } else if (camera_id == CAMERA_ID_OX03C10) { - probe->reg_addr = 0x300a; - probe->expected_data = 0x5803; - } else { - assert(false); - } + probe->reg_addr = ci->probe_reg_addr; + probe->expected_data = ci->probe_expected_data; probe->data_mask = 0; //buf_desc[1].size = buf_desc[1].length = 148; buf_desc[1].size = buf_desc[1].length = 196; buf_desc[1].type = CAM_CMD_BUF_I2C; auto power_settings = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - memset(power_settings.get(), 0, buf_desc[1].size); // power on struct cam_cmd_power *power = power_settings.get(); @@ -270,7 +150,7 @@ int CameraState::sensors_init() { power->count = 1; power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = (camera_id == CAMERA_ID_AR0231) ? 19200000 : 24000000; //Hz + power->power_settings[0].config_val_low = ci->mclk_frequency; power = power_set_wait(power, 1); // reset high @@ -423,10 +303,10 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b if (io_mem_handle != 0) { io_cfg[0].mem_handle[0] = io_mem_handle; io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = ci.frame_width, - .height = ci.frame_height + ci.extra_height, - .plane_stride = ci.frame_stride, - .slice_height = ci.frame_height + ci.extra_height, + .width = ci->frame_width, + .height = ci->frame_height + ci->extra_height, + .plane_stride = ci->frame_stride, + .slice_height = ci->frame_height + ci->extra_height, .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) .meta_size = 0x0, .meta_offset = 0x0, @@ -436,10 +316,10 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b .h_init = 0x0, .v_init = 0x0, }; - io_cfg[0].format = CAM_FORMAT_MIPI_RAW_12; // CAM_FORMAT_UBWC_TP10 for YUV + io_cfg[0].format = ci->mipi_format; // CAM_FORMAT_UBWC_TP10 for YUV io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; // CAM_COLOR_SPACE_BT601_FULL for YUV io_cfg[0].color_pattern = 0x5; // 0x0 for YUV - io_cfg[0].bpp = 0xc; + io_cfg[0].bpp = (ci->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); // bits per pixel io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; // CAM_ISP_IFE_OUT_RES_FULL for YUV io_cfg[0].fence = fence; io_cfg[0].direction = CAM_BUF_OUTPUT; @@ -516,57 +396,14 @@ void CameraState::enqueue_req_multi(int start, int n, bool dp) { // ******************* camera ******************* -void CameraState::camera_set_parameters() { - if (camera_id == CAMERA_ID_AR0231) { - dc_gain_factor = DC_GAIN_AR0231; - dc_gain_min_weight = DC_GAIN_MIN_WEIGHT_AR0231; - dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_AR0231; - dc_gain_on_grey = DC_GAIN_ON_GREY_AR0231; - dc_gain_off_grey = DC_GAIN_OFF_GREY_AR0231; - exposure_time_min = EXPOSURE_TIME_MIN_AR0231; - exposure_time_max = EXPOSURE_TIME_MAX_AR0231; - analog_gain_min_idx = ANALOG_GAIN_MIN_IDX_AR0231; - analog_gain_rec_idx = ANALOG_GAIN_REC_IDX_AR0231; - analog_gain_max_idx = ANALOG_GAIN_MAX_IDX_AR0231; - analog_gain_cost_delta = ANALOG_GAIN_COST_DELTA_AR0231; - analog_gain_cost_low = ANALOG_GAIN_COST_LOW_AR0231; - analog_gain_cost_high = ANALOG_GAIN_COST_HIGH_AR0231; - for (int i=0; i<=analog_gain_max_idx; i++) { - sensor_analog_gains[i] = sensor_analog_gains_AR0231[i]; - } - min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx]; - target_grey_factor = TARGET_GREY_FACTOR_AR0231; - } else if (camera_id == CAMERA_ID_OX03C10) { - dc_gain_factor = DC_GAIN_OX03C10; - dc_gain_min_weight = DC_GAIN_MIN_WEIGHT_OX03C10; - dc_gain_max_weight = DC_GAIN_MAX_WEIGHT_OX03C10; - dc_gain_on_grey = DC_GAIN_ON_GREY_OX03C10; - dc_gain_off_grey = DC_GAIN_OFF_GREY_OX03C10; - exposure_time_min = EXPOSURE_TIME_MIN_OX03C10; - exposure_time_max = EXPOSURE_TIME_MAX_OX03C10; - analog_gain_min_idx = ANALOG_GAIN_MIN_IDX_OX03C10; - analog_gain_rec_idx = ANALOG_GAIN_REC_IDX_OX03C10; - analog_gain_max_idx = ANALOG_GAIN_MAX_IDX_OX03C10; - analog_gain_cost_delta = ANALOG_GAIN_COST_DELTA_OX03C10; - analog_gain_cost_low = ANALOG_GAIN_COST_LOW_OX03C10; - analog_gain_cost_high = ANALOG_GAIN_COST_HIGH_OX03C10; - for (int i=0; i<=analog_gain_max_idx; i++) { - sensor_analog_gains[i] = sensor_analog_gains_OX03C10[i]; - } - min_ev = (exposure_time_min + VS_TIME_MIN_OX03C10) * sensor_analog_gains[analog_gain_min_idx]; - target_grey_factor = TARGET_GREY_FACTOR_OX03C10; - } else { - assert(false); - } - - max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; +void CameraState::sensor_set_parameters() { target_grey_fraction = 0.3; dc_gain_enabled = false; - dc_gain_weight = dc_gain_min_weight; - gain_idx = analog_gain_rec_idx; + dc_gain_weight = ci->dc_gain_min_weight; + gain_idx = ci->analog_gain_rec_idx; exposure_time = 5; - cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight) * sensor_analog_gains[gain_idx] * exposure_time; + cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight) * ci->sensor_analog_gains[gain_idx] * exposure_time; } void CameraState::camera_map_bufs(MultiCameraState *s) { @@ -584,20 +421,13 @@ void CameraState::camera_map_bufs(MultiCameraState *s) { enqueue_req_multi(1, FRAME_BUF_COUNT, 0); } -void CameraState::camera_init(MultiCameraState *s, VisionIpcServer * v, int camera_id_, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type) { +void CameraState::camera_init(MultiCameraState *s, VisionIpcServer * v, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type) { if (!enabled) return; - camera_id = camera_id_; LOGD("camera init %d", camera_num); - assert(camera_id < std::size(cameras_supported)); - ci = cameras_supported[camera_id]; - assert(ci.frame_width != 0); - request_id_last = 0; skipped = true; - camera_set_parameters(); - buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, yuv_type); camera_map_bufs(s); } @@ -616,22 +446,26 @@ void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num // init memorymanager for this camera mm.init(multi_cam_state->video0_fd); - // probe the sensor LOGD("-- Probing sensor %d", camera_num); - camera_id = CAMERA_ID_AR0231; - ret = sensors_init(); - if (ret != 0) { - // TODO: use build flag instead? - LOGD("AR0231 init failed, trying OX03C10"); - camera_id = CAMERA_ID_OX03C10; - ret = sensors_init(); - } - LOGD("-- Probing sensor %d done with %d", camera_num, ret); - if (ret != 0) { + + auto init_sensor_lambda = [this](SensorInfo *sensor) { + ci.reset(sensor); + int ret = sensors_init(); + if (ret == 0) { + sensor_set_parameters(); + } + return ret == 0; + }; + + // Try different sensors one by one until it success. + if (!init_sensor_lambda(new AR0231) && + !init_sensor_lambda(new OX03C10) && + !init_sensor_lambda(new OS04C10)) { LOGE("** sensor %d FAILED bringup, disabling", camera_num); enabled = false; return; } + LOGD("-- Probing sensor %d success", camera_num); // create session struct cam_req_mgr_session_info session_info = {}; @@ -647,69 +481,58 @@ void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num LOGD("acquire sensor dev"); LOG("-- Configuring sensor"); - uint32_t dt; - if (camera_id == CAMERA_ID_AR0231) { - sensors_i2c(init_array_ar0231, std::size(init_array_ar0231), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); - dt = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead - } else if (camera_id == CAMERA_ID_OX03C10) { - sensors_i2c(init_array_ox03c10, std::size(init_array_ox03c10), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); - // one is 0x2a, two are 0x2b - dt = 0x2c; - } else { - assert(false); - } - printf("dt is %x\n", dt); + sensors_i2c(ci->init_reg_array.data(), ci->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c // If you don't do this, the strobe GPIO is an output (even in reset it seems!) if (!enabled) return; struct cam_isp_in_port_info in_port_info = { - .res_type = (uint32_t[]){CAM_ISP_IFE_IN_RES_PHY_0, CAM_ISP_IFE_IN_RES_PHY_1, CAM_ISP_IFE_IN_RES_PHY_2}[camera_num], - - .lane_type = CAM_ISP_LANE_TYPE_DPHY, - .lane_num = 4, - .lane_cfg = 0x3210, - - .vc = 0x0, - .dt = dt, - .format = CAM_FORMAT_MIPI_RAW_12, - - .test_pattern = 0x2, // 0x3? - .usage_type = 0x0, - - .left_start = 0, - .left_stop = ci.frame_width - 1, - .left_width = ci.frame_width, - - .right_start = 0, - .right_stop = ci.frame_width - 1, - .right_width = ci.frame_width, - - .line_start = 0, - .line_stop = ci.frame_height + ci.extra_height - 1, - .height = ci.frame_height + ci.extra_height, - - .pixel_clk = 0x0, - .batch_size = 0x0, - .dsp_mode = CAM_ISP_DSP_MODE_NONE, - .hbi_cnt = 0x0, - .custom_csid = 0x0, - - .num_out_res = 0x1, - .data[0] = (struct cam_isp_out_port_info){ - .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, - .format = CAM_FORMAT_MIPI_RAW_12, - .width = ci.frame_width, - .height = ci.frame_height + ci.extra_height, - .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, - }, + .res_type = (uint32_t[]){CAM_ISP_IFE_IN_RES_PHY_0, CAM_ISP_IFE_IN_RES_PHY_1, CAM_ISP_IFE_IN_RES_PHY_2}[camera_num], + + .lane_type = CAM_ISP_LANE_TYPE_DPHY, + .lane_num = 4, + .lane_cfg = 0x3210, + + .vc = 0x0, + .dt = ci->frame_data_type, + .format = ci->mipi_format, + + .test_pattern = 0x2, // 0x3? + .usage_type = 0x0, + + .left_start = 0, + .left_stop = ci->frame_width - 1, + .left_width = ci->frame_width, + + .right_start = 0, + .right_stop = ci->frame_width - 1, + .right_width = ci->frame_width, + + .line_start = 0, + .line_stop = ci->frame_height + ci->extra_height - 1, + .height = ci->frame_height + ci->extra_height, + + .pixel_clk = 0x0, + .batch_size = 0x0, + .dsp_mode = CAM_ISP_DSP_MODE_NONE, + .hbi_cnt = 0x0, + .custom_csid = 0x0, + + .num_out_res = 0x1, + .data[0] = (struct cam_isp_out_port_info){ + .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, + .format = ci->mipi_format, + .width = ci->frame_width, + .height = ci->frame_height + ci->extra_height, + .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, + }, }; struct cam_isp_resource isp_resource = { - .resource_id = CAM_ISP_RES_ID_PORT, - .handle_type = CAM_HANDLE_USER_POINTER, - .res_hdl = (uint64_t)&in_port_info, - .length = sizeof(in_port_info), + .resource_id = CAM_ISP_RES_ID_PORT, + .handle_type = CAM_HANDLE_USER_POINTER, + .res_hdl = (uint64_t)&in_port_info, + .length = sizeof(in_port_info), }; auto isp_dev_handle_ = device_acquire(multi_cam_state->isp_fd, session_handle, &isp_resource); @@ -783,6 +606,7 @@ void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num LOGD("start csiphy: %d", ret); ret = device_control(multi_cam_state->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); LOGD("start isp: %d", ret); + assert(ret == 0); // TODO: this is unneeded, should we be doing the start i2c in a different way? //ret = device_control(sensor_fd, CAM_START_DEV, session_handle, sensor_dev_handle); @@ -790,9 +614,9 @@ void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num } void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - s->driver_cam.camera_init(s, v, s->driver_cam.camera_id, 20, device_id, ctx, VISION_STREAM_DRIVER); - s->road_cam.camera_init(s, v, s->road_cam.camera_id, 20, device_id, ctx, VISION_STREAM_ROAD); - s->wide_road_cam.camera_init(s, v, s->wide_road_cam.camera_id, 20, device_id, ctx, VISION_STREAM_WIDE_ROAD); + s->driver_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_DRIVER); + s->road_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_ROAD); + s->wide_road_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_WIDE_ROAD); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); } @@ -907,70 +731,6 @@ void cameras_close(MultiCameraState *s) { delete s->pm; } -std::map> CameraState::ar0231_build_register_lut(uint8_t *data) { - // This function builds a lookup table from register address, to a pair of indices in the - // buffer where to read this address. The buffer contains padding bytes, - // as well as markers to indicate the type of the next byte. - // - // 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address. - // Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional - // for contiguous ranges. See page 27-29 of the AR0231 Developer guide for more information. - - int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3}; - auto get_next_idx = [](int cur_idx) { - return (cur_idx % 3 == 1) ? cur_idx + 2 : cur_idx + 1; // Every third byte is padding - }; - - std::map> registers; - for (int register_row = 0; register_row < 2; register_row++) { - uint8_t *registers_raw = data + ci.frame_stride * register_row; - assert(registers_raw[0] == 0x0a); // Start of line - - int value_tag_count = 0; - int first_val_idx = 0; - uint16_t cur_addr = 0; - - for (int i = 1; i <= max_i[register_row]; i = get_next_idx(get_next_idx(i))) { - int val_idx = get_next_idx(i); - - uint8_t tag = registers_raw[i]; - uint16_t val = registers_raw[val_idx]; - - if (tag == 0xAA) { // Register MSB tag - cur_addr = val << 8; - } else if (tag == 0xA5) { // Register LSB tag - cur_addr |= val; - cur_addr -= 2; // Next value tag will increment address again - } else if (tag == 0x5A) { // Value tag - - // First tag - if (value_tag_count % 2 == 0) { - cur_addr += 2; - first_val_idx = val_idx; - } else { - registers[cur_addr] = std::make_pair(first_val_idx + ci.frame_stride * register_row, val_idx + ci.frame_stride * register_row); - } - - value_tag_count++; - } - } - } - return registers; -} - -std::map CameraState::ar0231_parse_registers(uint8_t *data, std::initializer_list addrs) { - if (ar0231_register_lut.empty()) { - ar0231_register_lut = ar0231_build_register_lut(data); - } - - std::map registers; - for (uint16_t addr : addrs) { - auto offset = ar0231_register_lut[addr]; - registers[addr] = ((uint16_t)data[offset.first] << 8) | data[offset.second]; - } - return registers; -} - void CameraState::handle_camera_event(void *evdat) { if (!enabled) return; struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; @@ -1007,9 +767,10 @@ void CameraState::handle_camera_event(void *evdat) { auto &meta_data = buf.camera_bufs_metadata[buf_idx]; meta_data.frame_id = main_id - idx_offset; + meta_data.request_id = real_id; meta_data.timestamp_sof = timestamp; exp_lock.lock(); - meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight); + meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); meta_data.high_conversion_gain = dc_gain_enabled; meta_data.integ_lines = exposure_time; meta_data.measured_grey_fraction = measured_grey_fraction; @@ -1030,22 +791,7 @@ void CameraState::handle_camera_event(void *evdat) { } void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) { - float score = 1e6; - if (camera_id == CAMERA_ID_AR0231) { - // Cost of ev diff - score = std::abs(desired_ev - (exp_t * exp_gain)) * 10; - // Cost of absolute gain - float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; - score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; - // Cost of changing gain - score += std::abs(exp_g_idx - gain_idx) * (score + 1.0) / 10.0; - } else if (camera_id == CAMERA_ID_OX03C10) { - score = std::abs(desired_ev - (exp_t * exp_gain)); - float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; - score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; - score += ((1 - analog_gain_cost_delta) + analog_gain_cost_delta * (exp_g_idx - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * std::abs(exp_g_idx - gain_idx) * 5.0; - } - + float score = ci->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); if (score < best_ev_score) { new_exp_t = exp_t; new_exp_g = exp_g_idx; @@ -1071,10 +817,10 @@ void CameraState::set_camera_exposure(float grey_frac) { const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; // Scale target grey between 0.1 and 0.4 depending on lighting conditions - float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); + float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + ci->target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); float target_grey = (1.0 - k_grey) * target_grey_fraction + k_grey * new_target_grey; - float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, min_ev, max_ev); + float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, ci->min_ev, ci->max_ev); float k = (1.0 - k_ev) / 3.0; desired_ev = (k * cur_ev[0]) + (k * cur_ev[1]) + (k * cur_ev[2]) + (k_ev * desired_ev); @@ -1085,21 +831,21 @@ void CameraState::set_camera_exposure(float grey_frac) { // Hysteresis around high conversion gain // We usually want this on since it results in lower noise, but turn off in very bright day scenes bool enable_dc_gain = dc_gain_enabled; - if (!enable_dc_gain && target_grey < dc_gain_on_grey) { + if (!enable_dc_gain && target_grey < ci->dc_gain_on_grey) { enable_dc_gain = true; - dc_gain_weight = dc_gain_min_weight; - } else if (enable_dc_gain && target_grey > dc_gain_off_grey) { + dc_gain_weight = ci->dc_gain_min_weight; + } else if (enable_dc_gain && target_grey > ci->dc_gain_off_grey) { enable_dc_gain = false; - dc_gain_weight = dc_gain_max_weight; + dc_gain_weight = ci->dc_gain_max_weight; } - if (enable_dc_gain && dc_gain_weight < dc_gain_max_weight) {dc_gain_weight += 1;} - if (!enable_dc_gain && dc_gain_weight > dc_gain_min_weight) {dc_gain_weight -= 1;} + if (enable_dc_gain && dc_gain_weight < ci->dc_gain_max_weight) {dc_gain_weight += 1;} + if (!enable_dc_gain && dc_gain_weight > ci->dc_gain_min_weight) {dc_gain_weight -= 1;} std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { - gain_bytes = Params().get("CameraDebugExpGain"); - time_bytes = Params().get("CameraDebugExpTime"); + gain_bytes = params.get("CameraDebugExpGain"); + time_bytes = params.get("CameraDebugExpTime"); } if (gain_bytes.size() > 0 && time_bytes.size() > 0) { @@ -1113,14 +859,14 @@ void CameraState::set_camera_exposure(float grey_frac) { } else { // Simple brute force optimizer to choose sensor parameters // to reach desired EV - for (int g = std::max((int)analog_gain_min_idx, gain_idx - 1); g <= std::min((int)analog_gain_max_idx, gain_idx + 1); g++) { - float gain = sensor_analog_gains[g] * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight); + for (int g = std::max((int)ci->analog_gain_min_idx, gain_idx - 1); g <= std::min((int)ci->analog_gain_max_idx, gain_idx + 1); g++) { + float gain = ci->sensor_analog_gains[g] * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); // Compute optimal time for given gain - int t = std::clamp(int(std::round(desired_ev / gain)), exposure_time_min, exposure_time_max); + int t = std::clamp(int(std::round(desired_ev / gain)), ci->exposure_time_min, ci->exposure_time_max); // Only go below recommended gain when absolutely necessary to not overexpose - if (g < analog_gain_rec_idx && t > 20 && g < gain_idx) { + if (g < ci->analog_gain_rec_idx && t > 20 && g < gain_idx) { continue; } @@ -1133,12 +879,12 @@ void CameraState::set_camera_exposure(float grey_frac) { measured_grey_fraction = grey_frac; target_grey_fraction = target_grey; - analog_gain_frac = sensor_analog_gains[new_exp_g]; + analog_gain_frac = ci->sensor_analog_gains[new_exp_g]; gain_idx = new_exp_g; exposure_time = new_exp_t; dc_gain_enabled = enable_dc_gain; - float gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight); + float gain = analog_gain_frac * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; exp_lock.unlock(); @@ -1151,59 +897,8 @@ void CameraState::set_camera_exposure(float grey_frac) { } // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", camera_num, 1e-9 * nanos_since_boot(), 1e-9 * buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - buf.cur_frame_data.timestamp_sof)); - if (camera_id == CAMERA_ID_AR0231) { - uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g; - struct i2c_random_wr_payload exp_reg_array[] = { - {0x3366, analog_gain_reg}, - {0x3362, (uint16_t)(dc_gain_enabled ? 0x1 : 0x0)}, - {0x3012, (uint16_t)exposure_time}, - }; - sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true); - } else if (camera_id == CAMERA_ID_OX03C10) { - // t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD - uint32_t hcg_time = exposure_time; - uint32_t lcg_time = hcg_time; - uint32_t spd_time = std::min(std::max((uint32_t)exposure_time, (exposure_time_max + VS_TIME_MAX_OX03C10) / 3), exposure_time_max + VS_TIME_MAX_OX03C10); - uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 40, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10); - - uint32_t real_gain = ox03c10_analog_gains_reg[new_exp_g]; - - struct i2c_random_wr_payload exp_reg_array[] = { - {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, - {0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF}, - {0x3541, spd_time>>8}, {0x3542, spd_time&0xFF}, - {0x35c2, vs_time&0xFF}, - - {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, - }; - sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false); - } -} - -static float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) { - // See AR0231 Developer Guide - page 36 - float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2); - float t0 = 55.0 - slope * (float)calib2; - return t0 + slope * (float)data_reg; -} - -static void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal::FrameData::Builder &framed){ - const uint8_t expected_preamble[] = {0x0a, 0xaa, 0x55, 0x20, 0xa5, 0x55}; - uint8_t *data = (uint8_t*)c->buf.cur_camera_buf->addr + c->ci.registers_offset; - - if (memcmp(data, expected_preamble, std::size(expected_preamble)) != 0){ - LOGE("unexpected register data found"); - return; - } - - auto registers = c->ar0231_parse_registers(data, {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}); - - uint32_t frame_id = ((uint32_t)registers[0x2000] << 16) | registers[0x2002]; - framed.setFrameIdSensor(frame_id); - - float temp_0 = ar0231_parse_temp_sensor(registers[0x30c6], registers[0x30c8], registers[0x20b0]); - float temp_1 = ar0231_parse_temp_sensor(registers[0x30ca], registers[0x30cc], registers[0x20b2]); - framed.setTemperaturesC({temp_0, temp_1}); + auto exp_reg_array = ci->getExposureRegisters(exposure_time, new_exp_g, dc_gain_enabled); + sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); } static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { @@ -1214,9 +909,7 @@ static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) framed.setFrameType(cereal::FrameData::FrameType::FRONT); fill_frame_data(framed, c->buf.cur_frame_data, c); - if (c->camera_id == CAMERA_ID_AR0231) { - ar0231_process_registers(s, c, framed); - } + c->ci->processRegisters(c, framed); s->pm->send("driverCameraState", msg); } @@ -1231,10 +924,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { } LOGT(c->buf.cur_frame_data.frame_id, "%s: Image set", c == &s->road_cam ? "RoadCamera" : "WideRoadCamera"); - if (c->camera_id == CAMERA_ID_AR0231) { - ar0231_process_registers(s, c, framed); - } - + c->ci->processRegisters(c, framed); s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); @@ -1282,6 +972,9 @@ void cameras_run(MultiCameraState *s) { event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp/1e6, event_data->u.frame_msg.sof_status); } + // for debugging + //do_exit = do_exit || event_data->u.frame_msg.frame_id > (30*20); + if (event_data->session_hdl == s->road_cam.session_handle) { s->road_cam.handle_camera_event(event_data); } else if (event_data->session_hdl == s->wide_road_cam.session_handle) { @@ -1292,6 +985,8 @@ void cameras_run(MultiCameraState *s) { LOGE("Unknown vidioc event source"); assert(false); } + } else { + LOGE("unhandled event %d\n", ev.type); } } else { LOGE("VIDIOC_DQEVENT failed, errno=%d", errno); diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h index 9e0109ab20..47ca578b99 100644 --- a/system/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -1,23 +1,20 @@ #pragma once -#include -#include +#include #include -#include - #include "system/camerad/cameras/camera_common.h" #include "system/camerad/cameras/camera_util.h" +#include "system/camerad/sensors/sensor.h" #include "common/params.h" #include "common/util.h" #define FRAME_BUF_COUNT 4 -#define ANALOG_GAIN_MAX_CNT 55 class CameraState { public: MultiCameraState *multi_cam_state; - CameraInfo ci; + std::unique_ptr ci; bool enabled; std::mutex exp_lock; @@ -28,32 +25,13 @@ public: int gain_idx; float analog_gain_frac; - int exposure_time_min; - int exposure_time_max; - - float dc_gain_factor; - int dc_gain_min_weight; - int dc_gain_max_weight; - float dc_gain_on_grey; - float dc_gain_off_grey; - - float sensor_analog_gains[ANALOG_GAIN_MAX_CNT]; - int analog_gain_min_idx; - int analog_gain_max_idx; - int analog_gain_rec_idx; - int analog_gain_cost_delta; - float analog_gain_cost_low; - float analog_gain_cost_high; - float cur_ev[3]; - float min_ev, max_ev; float best_ev_score; int new_exp_g; int new_exp_t; float measured_grey_fraction; float target_grey_fraction; - float target_grey_factor; unique_fd sensor_fd; unique_fd csiphy_fd; @@ -67,13 +45,11 @@ public: void sensors_start(); void camera_open(MultiCameraState *multi_cam_state, int camera_num, bool enabled); - void camera_set_parameters(); + void sensor_set_parameters(); void camera_map_bufs(MultiCameraState *s); - void camera_init(MultiCameraState *s, VisionIpcServer *v, int camera_id, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type); + void camera_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type); void camera_close(); - std::map ar0231_parse_registers(uint8_t *data, std::initializer_list addrs); - int32_t session_handle; int32_t sensor_dev_handle; int32_t isp_dev_handle; @@ -89,12 +65,10 @@ public: int frame_id_last; int idx_offset; bool skipped; - int camera_id; CameraBuf buf; MemoryManager mm; -private: void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); void enqueue_req_multi(int start, int n, bool dp); void enqueue_buffer(int i, bool dp); @@ -102,11 +76,11 @@ private: int sensors_init(); void sensors_poke(int request_id); - void sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); + void sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); - // Register parsing - std::map> ar0231_register_lut; - std::map> ar0231_build_register_lut(uint8_t *data); +private: + // for debugging + Params params; }; typedef struct MultiCameraState { diff --git a/system/camerad/cameras/camera_util.cc b/system/camerad/cameras/camera_util.cc index 74c81a878a..4fe38997ce 100644 --- a/system/camerad/cameras/camera_util.cc +++ b/system/camerad/cameras/camera_util.cc @@ -1,5 +1,7 @@ #include "system/camerad/cameras/camera_util.h" +#include + #include #include @@ -30,10 +32,10 @@ int do_cam_control(int fd, int op_code, void *handle, int size) { std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) { struct cam_acquire_dev_cmd cmd = { - .session_handle = session_handle, - .handle_type = CAM_HANDLE_USER_POINTER, - .num_resources = (uint32_t)(data ? num_resources : 0), - .resource_hdl = (uint64_t)data, + .session_handle = session_handle, + .handle_type = CAM_HANDLE_USER_POINTER, + .num_resources = (uint32_t)(data ? num_resources : 0), + .resource_hdl = (uint64_t)data, }; int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; @@ -41,9 +43,9 @@ std::optional device_acquire(int fd, int32_t session_handle, void *data int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) { struct cam_config_dev_cmd cmd = { - .session_handle = session_handle, - .dev_handle = dev_handle, - .packet_handle = packet_handle, + .session_handle = session_handle, + .dev_handle = dev_handle, + .packet_handle = packet_handle, }; return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); } @@ -111,6 +113,7 @@ void *MemoryManager::alloc_buf(int size, uint32_t *handle) { size_lookup[ptr] = size; } lock.unlock(); + memset(ptr, 0, size); return ptr; } diff --git a/system/camerad/cameras/camera_util.h b/system/camerad/cameras/camera_util.h index b36f404c0f..891ce3e793 100644 --- a/system/camerad/cameras/camera_util.h +++ b/system/camerad/cameras/camera_util.h @@ -1,6 +1,6 @@ #pragma once - #include +#include #include #include #include diff --git a/system/camerad/imgproc/conv.cl b/system/camerad/imgproc/conv.cl deleted file mode 100644 index a7115ae76c..0000000000 --- a/system/camerad/imgproc/conv.cl +++ /dev/null @@ -1,110 +0,0 @@ -// const __constant float3 rgb_weights = (0.299, 0.587, 0.114); // opencv rgb2gray weights -// const __constant float3 bgr_weights = (0.114, 0.587, 0.299); // bgr2gray weights - -// convert input rgb image to single channel then conv -__kernel void rgb2gray_conv2d( - const __global uchar * input, - __global short * output, - __constant short * filter, - __local uchar3 * cached -) -{ - const int rowOffset = get_global_id(1) * IMAGE_W; - const int my = get_global_id(0) + rowOffset; - - const int localRowLen = TWICE_HALF_FILTER_SIZE + get_local_size(0); - const int localRowOffset = ( get_local_id(1) + HALF_FILTER_SIZE ) * localRowLen; - const int myLocal = localRowOffset + get_local_id(0) + HALF_FILTER_SIZE; - - // cache local pixels - cached[ myLocal ].x = input[ my * 3 ]; // r - cached[ myLocal ].y = input[ my * 3 + 1]; // g - cached[ myLocal ].z = input[ my * 3 + 2]; // b - - // pad - if ( - get_global_id(0) < HALF_FILTER_SIZE || - get_global_id(0) > IMAGE_W - HALF_FILTER_SIZE - 1 || - get_global_id(1) < HALF_FILTER_SIZE || - get_global_id(1) > IMAGE_H - HALF_FILTER_SIZE - 1 - ) - { - barrier(CLK_LOCAL_MEM_FENCE); - return; - } - else - { - int localColOffset = -1; - int globalColOffset = -1; - - // cache extra - if ( get_local_id(0) < HALF_FILTER_SIZE ) - { - localColOffset = get_local_id(0); - globalColOffset = -HALF_FILTER_SIZE; - - cached[ localRowOffset + get_local_id(0) ].x = input[ my * 3 - HALF_FILTER_SIZE * 3 ]; - cached[ localRowOffset + get_local_id(0) ].y = input[ my * 3 - HALF_FILTER_SIZE * 3 + 1]; - cached[ localRowOffset + get_local_id(0) ].z = input[ my * 3 - HALF_FILTER_SIZE * 3 + 2]; - } - else if ( get_local_id(0) >= get_local_size(0) - HALF_FILTER_SIZE ) - { - localColOffset = get_local_id(0) + TWICE_HALF_FILTER_SIZE; - globalColOffset = HALF_FILTER_SIZE; - - cached[ myLocal + HALF_FILTER_SIZE ].x = input[ my * 3 + HALF_FILTER_SIZE * 3 ]; - cached[ myLocal + HALF_FILTER_SIZE ].y = input[ my * 3 + HALF_FILTER_SIZE * 3 + 1]; - cached[ myLocal + HALF_FILTER_SIZE ].z = input[ my * 3 + HALF_FILTER_SIZE * 3 + 2]; - } - - - if ( get_local_id(1) < HALF_FILTER_SIZE ) - { - cached[ get_local_id(1) * localRowLen + get_local_id(0) + HALF_FILTER_SIZE ].x = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 ]; - cached[ get_local_id(1) * localRowLen + get_local_id(0) + HALF_FILTER_SIZE ].y = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + 1]; - cached[ get_local_id(1) * localRowLen + get_local_id(0) + HALF_FILTER_SIZE ].z = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + 2]; - if (localColOffset > 0) - { - cached[ get_local_id(1) * localRowLen + localColOffset ].x = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3]; - cached[ get_local_id(1) * localRowLen + localColOffset ].y = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 1]; - cached[ get_local_id(1) * localRowLen + localColOffset ].z = input[ my * 3 - HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 2]; - } - } - else if ( get_local_id(1) >= get_local_size(1) -HALF_FILTER_SIZE ) - { - int offset = ( get_local_id(1) + TWICE_HALF_FILTER_SIZE ) * localRowLen; - cached[ offset + get_local_id(0) + HALF_FILTER_SIZE ].x = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 ]; - cached[ offset + get_local_id(0) + HALF_FILTER_SIZE ].y = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + 1]; - cached[ offset + get_local_id(0) + HALF_FILTER_SIZE ].z = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + 2]; - if (localColOffset > 0) - { - cached[ offset + localColOffset ].x = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3]; - cached[ offset + localColOffset ].y = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 1]; - cached[ offset + localColOffset ].z = input[ my * 3 + HALF_FILTER_SIZE_IMAGE_W * 3 + globalColOffset * 3 + 2]; - } - } - - // sync - barrier(CLK_LOCAL_MEM_FENCE); - - // perform convolution - int fIndex = 0; - short sum = 0; - - for (int r = -HALF_FILTER_SIZE; r <= HALF_FILTER_SIZE; r++) - { - int curRow = r * localRowLen; - for (int c = -HALF_FILTER_SIZE; c <= HALF_FILTER_SIZE; c++, fIndex++) - { - if (!FLIP_RB){ - // sum += dot(rgb_weights, cached[ myLocal + curRow + c ]) * filter[ fIndex ]; - sum += (cached[ myLocal + curRow + c ].x / 3 + cached[ myLocal + curRow + c ].y / 2 + cached[ myLocal + curRow + c ].z / 9) * filter[ fIndex ]; - } else { - // sum += dot(bgr_weights, cached[ myLocal + curRow + c ]) * filter[ fIndex ]; - sum += (cached[ myLocal + curRow + c ].x / 9 + cached[ myLocal + curRow + c ].y / 2 + cached[ myLocal + curRow + c ].z / 3) * filter[ fIndex ]; - } - } - } - output[my] = sum; - } -} \ No newline at end of file diff --git a/system/camerad/imgproc/pool.cl b/system/camerad/imgproc/pool.cl deleted file mode 100644 index d674b5f363..0000000000 --- a/system/camerad/imgproc/pool.cl +++ /dev/null @@ -1,34 +0,0 @@ -// calculate variance in each subregion -__kernel void var_pool( - const __global char * input, - __global ushort * output // should not be larger than 128*128 so uint16 -) -{ - const int xidx = get_global_id(0) + ROI_X_MIN; - const int yidx = get_global_id(1) + ROI_Y_MIN; - - const int size = X_PITCH * Y_PITCH; - - float fsum = 0; - char mean, max; - - for (int i = 0; i < size; i++) { - int x_offset = i % X_PITCH; - int y_offset = i / X_PITCH; - fsum += input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X]; - max = input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X]>max ? input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X]:max; - } - - mean = convert_char_rte(fsum / size); - - float fvar = 0; - for (int i = 0; i < size; i++) { - int x_offset = i % X_PITCH; - int y_offset = i / X_PITCH; - fvar += (input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X] - mean) * (input[xidx*X_PITCH + yidx*Y_PITCH*FULL_STRIDE_X + x_offset + y_offset*FULL_STRIDE_X] - mean); - } - - fvar = fvar / size; - - output[(xidx-ROI_X_MIN)+(yidx-ROI_Y_MIN)*(ROI_X_MAX-ROI_X_MIN+1)] = convert_ushort_rte(5 * fvar + convert_float_rte(max)); -} \ No newline at end of file diff --git a/system/camerad/imgproc/utils.cc b/system/camerad/imgproc/utils.cc deleted file mode 100644 index a7bbeb9e86..0000000000 --- a/system/camerad/imgproc/utils.cc +++ /dev/null @@ -1,106 +0,0 @@ -#include "system/camerad/imgproc/utils.h" - -#include -#include -#include -#include -#include - -const int16_t lapl_conv_krnl[9] = {0, 1, 0, - 1, -4, 1, - 0, 1, 0}; - -// calculate score based on laplacians in one area -uint16_t get_lapmap_one(const int16_t *lap, int x_pitch, int y_pitch) { - const int size = x_pitch * y_pitch; - // avg and max of roi - int16_t max = 0; - int sum = 0; - for (int i = 0; i < size; ++i) { - const int16_t v = lap[i]; - sum += v; - if (v > max) max = v; - } - - const int16_t mean = sum / size; - - // var of roi - int var = 0; - for (int i = 0; i < size; ++i) { - var += std::pow(lap[i] - mean, 2); - } - - const float fvar = (float)var / size; - return std::min(5 * fvar + max, (float)65535); -} - -bool is_blur(const uint16_t *lapmap, const size_t size) { - float bad_sum = 0; - for (int i = 0; i < size; i++) { - if (lapmap[i] < LM_THRESH) { - bad_sum += 1 / (float)size; - } - } - return (bad_sum > LM_PREC_THRESH); -} - -static cl_program build_conv_program(cl_device_id device_id, cl_context context, int image_w, int image_h, int filter_size) { - char args[4096]; - snprintf(args, sizeof(args), - "-cl-fast-relaxed-math -cl-denorms-are-zero " - "-DIMAGE_W=%d -DIMAGE_H=%d -DFLIP_RB=%d " - "-DFILTER_SIZE=%d -DHALF_FILTER_SIZE=%d -DTWICE_HALF_FILTER_SIZE=%d -DHALF_FILTER_SIZE_IMAGE_W=%d", - image_w, image_h, 1, - filter_size, filter_size/2, (filter_size/2)*2, (filter_size/2)*image_w); - return cl_program_from_file(context, device_id, "imgproc/conv.cl", args); -} - -LapConv::LapConv(cl_device_id device_id, cl_context ctx, int rgb_width, int rgb_height, int rgb_stride, int filter_size) - : width(rgb_width / NUM_SEGMENTS_X), height(rgb_height / NUM_SEGMENTS_Y), rgb_stride(rgb_stride), - roi_buf(width * height * 3), result_buf(width * height) { - - prg = build_conv_program(device_id, ctx, width, height, filter_size); - krnl = CL_CHECK_ERR(clCreateKernel(prg, "rgb2gray_conv2d", &err)); - // TODO: Removed CL_MEM_SVM_FINE_GRAIN_BUFFER, confirm it doesn't matter - roi_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_WRITE, roi_buf.size() * sizeof(roi_buf[0]), NULL, &err)); - result_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_WRITE, result_buf.size() * sizeof(result_buf[0]), NULL, &err)); - filter_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_ONLY | CL_MEM_COPY_HOST_PTR, - 9 * sizeof(int16_t), (void *)&lapl_conv_krnl, &err)); -} - -LapConv::~LapConv() { - CL_CHECK(clReleaseMemObject(roi_cl)); - CL_CHECK(clReleaseMemObject(result_cl)); - CL_CHECK(clReleaseMemObject(filter_cl)); - CL_CHECK(clReleaseKernel(krnl)); - CL_CHECK(clReleaseProgram(prg)); -} - -uint16_t LapConv::Update(cl_command_queue q, const uint8_t *rgb_buf, const int roi_id) { - // sharpness scores - const int x_offset = ROI_X_MIN + roi_id % (ROI_X_MAX - ROI_X_MIN + 1); - const int y_offset = ROI_Y_MIN + roi_id / (ROI_X_MAX - ROI_X_MIN + 1); - - const uint8_t *rgb_offset = rgb_buf + y_offset * height * rgb_stride + x_offset * width * 3; - for (int i = 0; i < height; ++i) { - memcpy(&roi_buf[i * width * 3], &rgb_offset[i * rgb_stride], width * 3); - } - - constexpr int local_mem_size = (CONV_LOCAL_WORKSIZE + 2 * (3 / 2)) * (CONV_LOCAL_WORKSIZE + 2 * (3 / 2)) * (3 * sizeof(uint8_t)); - const size_t global_work_size[] = {(size_t)width, (size_t)height}; - const size_t local_work_size[] = {CONV_LOCAL_WORKSIZE, CONV_LOCAL_WORKSIZE}; - - CL_CHECK(clEnqueueWriteBuffer(q, roi_cl, CL_TRUE, 0, roi_buf.size() * sizeof(roi_buf[0]), roi_buf.data(), 0, 0, 0)); - CL_CHECK(clSetKernelArg(krnl, 0, sizeof(cl_mem), (void *)&roi_cl)); - CL_CHECK(clSetKernelArg(krnl, 1, sizeof(cl_mem), (void *)&result_cl)); - CL_CHECK(clSetKernelArg(krnl, 2, sizeof(cl_mem), (void *)&filter_cl)); - CL_CHECK(clSetKernelArg(krnl, 3, local_mem_size, 0)); - cl_event conv_event; - CL_CHECK(clEnqueueNDRangeKernel(q, krnl, 2, NULL, global_work_size, local_work_size, 0, 0, &conv_event)); - CL_CHECK(clWaitForEvents(1, &conv_event)); - CL_CHECK(clReleaseEvent(conv_event)); - CL_CHECK(clEnqueueReadBuffer(q, result_cl, CL_TRUE, 0, - result_buf.size() * sizeof(result_buf[0]), result_buf.data(), 0, 0, 0)); - - return get_lapmap_one(result_buf.data(), width, height); -} diff --git a/system/camerad/imgproc/utils.h b/system/camerad/imgproc/utils.h deleted file mode 100644 index 94323b15c5..0000000000 --- a/system/camerad/imgproc/utils.h +++ /dev/null @@ -1,37 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "common/clutil.h" - -#define NUM_SEGMENTS_X 8 -#define NUM_SEGMENTS_Y 6 - -#define ROI_X_MIN 1 -#define ROI_X_MAX 6 -#define ROI_Y_MIN 2 -#define ROI_Y_MAX 3 - -#define LM_THRESH 120 -#define LM_PREC_THRESH 0.9 // 90 perc is blur -#define CONV_LOCAL_WORKSIZE 16 - -class LapConv { -public: - LapConv(cl_device_id device_id, cl_context ctx, int rgb_width, int rgb_height, int rgb_stride, int filter_size); - ~LapConv(); - uint16_t Update(cl_command_queue q, const uint8_t *rgb_buf, const int roi_id); - -private: - cl_mem roi_cl, result_cl, filter_cl; - cl_program prg; - cl_kernel krnl; - const int width, height; - const int rgb_stride; - std::vector roi_buf; - std::vector result_buf; -}; - -bool is_blur(const uint16_t *lapmap, const size_t size); diff --git a/system/camerad/main.cc b/system/camerad/main.cc index 35a3329f30..19de21c9bb 100644 --- a/system/camerad/main.cc +++ b/system/camerad/main.cc @@ -8,7 +8,7 @@ int main(int argc, char *argv[]) { if (Hardware::PC()) { - printf("camerad is not meant to run on PC\n"); + printf("exiting, camerad is not meant to run on PC\n"); return 0; } diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc new file mode 100644 index 0000000000..1ca4b3f1ad --- /dev/null +++ b/system/camerad/sensors/ar0231.cc @@ -0,0 +1,171 @@ +#include + +#include "common/swaglog.h" +#include "system/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/camera_qcom2.h" +#include "system/camerad/sensors/sensor.h" + +namespace { + +const size_t AR0231_REGISTERS_HEIGHT = 2; +// TODO: this extra height is universal and doesn't apply per camera +const size_t AR0231_STATS_HEIGHT = 2 + 8; + +const float sensor_analog_gains_AR0231[] = { + 1.0 / 8.0, 2.0 / 8.0, 2.0 / 7.0, 3.0 / 7.0, // 0, 1, 2, 3 + 3.0 / 6.0, 4.0 / 6.0, 4.0 / 5.0, 5.0 / 5.0, // 4, 5, 6, 7 + 5.0 / 4.0, 6.0 / 4.0, 6.0 / 3.0, 7.0 / 3.0, // 8, 9, 10, 11 + 7.0 / 2.0, 8.0 / 2.0, 8.0 / 1.0}; // 12, 13, 14, 15 = bypass + +std::map> ar0231_build_register_lut(CameraState *c, uint8_t *data) { + // This function builds a lookup table from register address, to a pair of indices in the + // buffer where to read this address. The buffer contains padding bytes, + // as well as markers to indicate the type of the next byte. + // + // 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address. + // Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional + // for contiguous ranges. See page 27-29 of the AR0231 Developer guide for more information. + + int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3}; + auto get_next_idx = [](int cur_idx) { + return (cur_idx % 3 == 1) ? cur_idx + 2 : cur_idx + 1; // Every third byte is padding + }; + + std::map> registers; + for (int register_row = 0; register_row < 2; register_row++) { + uint8_t *registers_raw = data + c->ci->frame_stride * register_row; + assert(registers_raw[0] == 0x0a); // Start of line + + int value_tag_count = 0; + int first_val_idx = 0; + uint16_t cur_addr = 0; + + for (int i = 1; i <= max_i[register_row]; i = get_next_idx(get_next_idx(i))) { + int val_idx = get_next_idx(i); + + uint8_t tag = registers_raw[i]; + uint16_t val = registers_raw[val_idx]; + + if (tag == 0xAA) { // Register MSB tag + cur_addr = val << 8; + } else if (tag == 0xA5) { // Register LSB tag + cur_addr |= val; + cur_addr -= 2; // Next value tag will increment address again + } else if (tag == 0x5A) { // Value tag + + // First tag + if (value_tag_count % 2 == 0) { + cur_addr += 2; + first_val_idx = val_idx; + } else { + registers[cur_addr] = std::make_pair(first_val_idx + c->ci->frame_stride * register_row, val_idx + c->ci->frame_stride * register_row); + } + + value_tag_count++; + } + } + } + return registers; +} + +float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) { + // See AR0231 Developer Guide - page 36 + float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2); + float t0 = 55.0 - slope * (float)calib2; + return t0 + slope * (float)data_reg; +} + +} // namespace + +AR0231::AR0231() { + image_sensor = cereal::FrameData::ImageSensor::AR0231; + data_word = true; + frame_width = FRAME_WIDTH; + frame_height = FRAME_HEIGHT; + frame_stride = FRAME_STRIDE; + extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT; + + registers_offset = 0; + frame_offset = AR0231_REGISTERS_HEIGHT; + stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT; + + start_reg_array.assign(std::begin(start_reg_array_ar0231), std::end(start_reg_array_ar0231)); + init_reg_array.assign(std::begin(init_array_ar0231), std::end(init_array_ar0231)); + probe_reg_addr = 0x3000; + probe_expected_data = 0x354; + mipi_format = CAM_FORMAT_MIPI_RAW_12; + frame_data_type = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead + mclk_frequency = 19200000; //Hz + + dc_gain_factor = 2.5; + dc_gain_min_weight = 0; + dc_gain_max_weight = 1; + dc_gain_on_grey = 0.2; + dc_gain_off_grey = 0.3; + exposure_time_min = 2; // with HDR, fastest ss + exposure_time_max = 0x0855; // with HDR, slowest ss, 40ms + analog_gain_min_idx = 0x1; // 0.25x + analog_gain_rec_idx = 0x6; // 0.8x + analog_gain_max_idx = 0xD; // 4.0x + analog_gain_cost_delta = 0; + analog_gain_cost_low = 0.1; + analog_gain_cost_high = 5.0; + for (int i = 0; i <= analog_gain_max_idx; i++) { + sensor_analog_gains[i] = sensor_analog_gains_AR0231[i]; + } + min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx]; + max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; + target_grey_factor = 1.0; +} + +void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const { + const uint8_t expected_preamble[] = {0x0a, 0xaa, 0x55, 0x20, 0xa5, 0x55}; + uint8_t *data = (uint8_t *)c->buf.cur_camera_buf->addr + c->ci->registers_offset; + + if (memcmp(data, expected_preamble, std::size(expected_preamble)) != 0) { + LOGE("unexpected register data found"); + return; + } + + if (ar0231_register_lut.empty()) { + ar0231_register_lut = ar0231_build_register_lut(c, data); + } + std::map registers; + for (uint16_t addr : {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}) { + auto offset = ar0231_register_lut[addr]; + registers[addr] = ((uint16_t)data[offset.first] << 8) | data[offset.second]; + } + + uint32_t frame_id = ((uint32_t)registers[0x2000] << 16) | registers[0x2002]; + framed.setFrameIdSensor(frame_id); + + float temp_0 = ar0231_parse_temp_sensor(registers[0x30c6], registers[0x30c8], registers[0x20b0]); + float temp_1 = ar0231_parse_temp_sensor(registers[0x30ca], registers[0x30cc], registers[0x20b2]); + framed.setTemperaturesC({temp_0, temp_1}); +} + + +std::vector AR0231::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { + uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g; + return { + {0x3366, analog_gain_reg}, + {0x3362, (uint16_t)(dc_gain_enabled ? 0x1 : 0x0)}, + {0x3012, (uint16_t)exposure_time}, + }; +} + +int AR0231::getSlaveAddress(int port) const { + assert(port >= 0 && port <= 2); + return (int[]){0x20, 0x30, 0x20}[port]; +} + +float AR0231::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { + // Cost of ev diff + float score = std::abs(desired_ev - (exp_t * exp_gain)) * 10; + // Cost of absolute gain + float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; + score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; + // Cost of changing gain + score += std::abs(exp_g_idx - gain_idx) * (score + 1.0) / 10.0; + return score; +} diff --git a/system/camerad/sensors/ar0231_registers.h b/system/camerad/sensors/ar0231_registers.h new file mode 100644 index 0000000000..6c4c251e8e --- /dev/null +++ b/system/camerad/sensors/ar0231_registers.h @@ -0,0 +1,119 @@ +#pragma once + +const struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}}; +const struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}}; + +const struct i2c_random_wr_payload init_array_ar0231[] = { + {0x301A, 0x0018}, // RESET_REGISTER + + // CLOCK Settings + // input clock is 19.2 / 2 * 0x37 = 528 MHz + // pixclk is 528 / 6 = 88 MHz + // full roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*FRAME_LENGTH_LINES)) = 39.99 ms + // img roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*Y_OUTPUT_CONTROL)) = 22.85 ms + {0x302A, 0x0006}, // VT_PIX_CLK_DIV + {0x302C, 0x0001}, // VT_SYS_CLK_DIV + {0x302E, 0x0002}, // PRE_PLL_CLK_DIV + {0x3030, 0x0037}, // PLL_MULTIPLIER + {0x3036, 0x000C}, // OP_PIX_CLK_DIV + {0x3038, 0x0001}, // OP_SYS_CLK_DIV + + // FORMAT + {0x3040, 0xC000}, // READ_MODE + {0x3004, 0x0000}, // X_ADDR_START_ + {0x3008, 0x0787}, // X_ADDR_END_ + {0x3002, 0x0000}, // Y_ADDR_START_ + {0x3006, 0x04B7}, // Y_ADDR_END_ + {0x3032, 0x0000}, // SCALING_MODE + {0x30A2, 0x0001}, // X_ODD_INC_ + {0x30A6, 0x0001}, // Y_ODD_INC_ + {0x3402, 0x0788}, // X_OUTPUT_CONTROL + {0x3404, 0x04B8}, // Y_OUTPUT_CONTROL + {0x3064, 0x1982}, // SMIA_TEST + {0x30BA, 0x11F2}, // DIGITAL_CTRL + + // Enable external trigger and disable GPIO outputs + {0x30CE, 0x0120}, // SLAVE_SH_SYNC_MODE | FRAME_START_MODE + {0x340A, 0xE0}, // GPIO3_INPUT_DISABLE | GPIO2_INPUT_DISABLE | GPIO1_INPUT_DISABLE + {0x340C, 0x802}, // GPIO_HIDRV_EN | GPIO0_ISEL=2 + + // Readout timing + {0x300C, 0x0672}, // LINE_LENGTH_PCK (valid for 3-exposure HDR) + {0x300A, 0x0855}, // FRAME_LENGTH_LINES + {0x3042, 0x0000}, // EXTRA_DELAY + + // Readout Settings + {0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI + {0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12 + {0x3342, 0x1212}, // MIPI_F1_PDT_EDT + {0x3346, 0x1212}, // MIPI_F2_PDT_EDT + {0x334A, 0x1212}, // MIPI_F3_PDT_EDT + {0x334E, 0x1212}, // MIPI_F4_PDT_EDT + {0x3344, 0x0011}, // MIPI_F1_VDT_VC + {0x3348, 0x0111}, // MIPI_F2_VDT_VC + {0x334C, 0x0211}, // MIPI_F3_VDT_VC + {0x3350, 0x0311}, // MIPI_F4_VDT_VC + {0x31B0, 0x0053}, // FRAME_PREAMBLE + {0x31B2, 0x003B}, // LINE_PREAMBLE + {0x301A, 0x001C}, // RESET_REGISTER + + // Noise Corrections + {0x3092, 0x0C24}, // ROW_NOISE_CONTROL + {0x337A, 0x0C80}, // DBLC_SCALE0 + {0x3370, 0x03B1}, // DBLC + {0x3044, 0x0400}, // DARK_CONTROL + + // Enable temperature sensor + {0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG + {0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG + + // Enable dead pixel correction using + // the 1D line correction scheme + {0x31E0, 0x0003}, + + // HDR Settings + {0x3082, 0x0004}, // OPERATION_MODE_CTRL + {0x3238, 0x0444}, // EXPOSURE_RATIO + + {0x1008, 0x0361}, // FINE_INTEGRATION_TIME_MIN + {0x100C, 0x0589}, // FINE_INTEGRATION_TIME2_MIN + {0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN + {0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN + + // TODO: do these have to be lower than LINE_LENGTH_PCK? + {0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_ + {0x321E, 0x0894}, // FINE_INTEGRATION_TIME2 + + {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? + {0x33DA, 0x0000}, // COMPANDING + {0x318E, 0x0200}, // PRE_HDR_GAIN_EN + + // DLO Settings + {0x3100, 0x4000}, // DLO_CONTROL0 + {0x3280, 0x0CCC}, // T1 G1 + {0x3282, 0x0CCC}, // T1 R + {0x3284, 0x0CCC}, // T1 B + {0x3286, 0x0CCC}, // T1 G2 + {0x3288, 0x0FA0}, // T2 G1 + {0x328A, 0x0FA0}, // T2 R + {0x328C, 0x0FA0}, // T2 B + {0x328E, 0x0FA0}, // T2 G2 + + // Initial Gains + {0x3022, 0x0001}, // GROUPED_PARAMETER_HOLD_ + {0x3366, 0xFF77}, // ANALOG_GAIN (1x) + + {0x3060, 0x3333}, // ANALOG_COLOR_GAIN + + {0x3362, 0x0000}, // DC GAIN + + {0x305A, 0x00F8}, // red gain + {0x3058, 0x0122}, // blue gain + {0x3056, 0x009A}, // g1 gain + {0x305C, 0x009A}, // g2 gain + + {0x3022, 0x0000}, // GROUPED_PARAMETER_HOLD_ + + // Initial Integration Time + {0x3012, 0x0005}, +}; diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc new file mode 100644 index 0000000000..449e06be83 --- /dev/null +++ b/system/camerad/sensors/os04c10.cc @@ -0,0 +1,105 @@ +#include "system/camerad/sensors/sensor.h" + +namespace { + +const float sensor_analog_gains_OS04C10[] = { + 1.0, 1.0625, 1.125, 1.1875, 1.25, 1.3125, 1.375, 1.4375, 1.5, 1.5625, 1.6875, + 1.8125, 1.9375, 2.0, 2.125, 2.25, 2.375, 2.5, 2.625, 2.75, 2.875, 3.0, + 3.125, 3.375, 3.625, 3.875, 4.0, 4.25, 4.5, 4.75, 5.0, 5.25, 5.5, + 5.75, 6.0, 6.25, 6.5, 7.0, 7.5, 8.0, 8.5, 9.0, 9.5, 10.0, + 10.5, 11.0, 11.5, 12.0, 12.5, 13.0, 13.5, 14.0, 14.5, 15.0, 15.5}; + +const uint32_t os04c10_analog_gains_reg[] = { + 0x100, 0x110, 0x120, 0x130, 0x140, 0x150, 0x160, 0x170, 0x180, 0x190, 0x1B0, + 0x1D0, 0x1F0, 0x200, 0x220, 0x240, 0x260, 0x280, 0x2A0, 0x2C0, 0x2E0, 0x300, + 0x320, 0x360, 0x3A0, 0x3E0, 0x400, 0x440, 0x480, 0x4C0, 0x500, 0x540, 0x580, + 0x5C0, 0x600, 0x640, 0x680, 0x700, 0x780, 0x800, 0x880, 0x900, 0x980, 0xA00, + 0xA80, 0xB00, 0xB80, 0xC00, 0xC80, 0xD00, 0xD80, 0xE00, 0xE80, 0xF00, 0xF80}; + +const uint32_t VS_TIME_MIN_OS04C10 = 1; +//const uint32_t VS_TIME_MAX_OS04C10 = 34; // vs < 35 + +} // namespace + +OS04C10::OS04C10() { + image_sensor = cereal::FrameData::ImageSensor::OS04C10; + data_word = false; + + frame_width = 1920; + frame_height = 1080; + frame_stride = (1920*10/8); + + /* + frame_width = 0xa80; + frame_height = 0x5f0; + frame_stride = 0xd20; + */ + + extra_height = 0; + frame_offset = 0; + + start_reg_array.assign(std::begin(start_reg_array_os04c10), std::end(start_reg_array_os04c10)); + init_reg_array.assign(std::begin(init_array_os04c10), std::end(init_array_os04c10)); + probe_reg_addr = 0x300a; + probe_expected_data = 0x5304; + mipi_format = CAM_FORMAT_MIPI_RAW_10; + frame_data_type = 0x2b; + mclk_frequency = 24000000; // Hz + + dc_gain_factor = 7.32; + dc_gain_min_weight = 1; // always on is fine + dc_gain_max_weight = 1; + dc_gain_on_grey = 0.9; + dc_gain_off_grey = 1.0; + exposure_time_min = 2; // 1x + exposure_time_max = 2016; + analog_gain_min_idx = 0x0; + analog_gain_rec_idx = 0x0; // 1x + analog_gain_max_idx = 0x36; + analog_gain_cost_delta = -1; + analog_gain_cost_low = 0.4; + analog_gain_cost_high = 6.4; + for (int i = 0; i <= analog_gain_max_idx; i++) { + sensor_analog_gains[i] = sensor_analog_gains_OS04C10[i]; + } + min_ev = (exposure_time_min + VS_TIME_MIN_OS04C10) * sensor_analog_gains[analog_gain_min_idx]; + max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; + target_grey_factor = 0.01; +} + +std::vector OS04C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { + // t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD + uint32_t hcg_time = exposure_time; + //uint32_t lcg_time = hcg_time; + //uint32_t spd_time = std::min(std::max((uint32_t)exposure_time, (exposure_time_max + VS_TIME_MAX_OS04C10) / 3), exposure_time_max + VS_TIME_MAX_OS04C10); + //uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 40, VS_TIME_MIN_OS04C10), VS_TIME_MAX_OS04C10); + + uint32_t real_gain = os04c10_analog_gains_reg[new_exp_g]; + + hcg_time = 100; + real_gain = 0x320; + + return { + {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, + //{0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF}, + //{0x3541, spd_time>>8}, {0x3542, spd_time&0xFF}, + //{0x35c2, vs_time&0xFF}, + + {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, + }; +} + +int OS04C10::getSlaveAddress(int port) const { + assert(port >= 0 && port <= 2); + return (int[]){0x6C, 0x20, 0x6C}[port]; +} + +float OS04C10::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { + float score = std::abs(desired_ev - (exp_t * exp_gain)); + float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; + score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; + score += ((1 - analog_gain_cost_delta) + + analog_gain_cost_delta * (exp_g_idx - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * + std::abs(exp_g_idx - gain_idx) * 5.0; + return score; +} diff --git a/system/camerad/sensors/os04c10_registers.h b/system/camerad/sensors/os04c10_registers.h new file mode 100644 index 0000000000..ad91a02950 --- /dev/null +++ b/system/camerad/sensors/os04c10_registers.h @@ -0,0 +1,298 @@ +#pragma once + +const struct i2c_random_wr_payload start_reg_array_os04c10[] = {{0x100, 1}}; +const struct i2c_random_wr_payload stop_reg_array_os04c10[] = {{0x100, 0}}; + +const struct i2c_random_wr_payload init_array_os04c10[] = { + // OS04C10_AA_00_02_17_wAO_1920x1080_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz + {0x0103, 0x01}, + {0x0301, 0x84}, + {0x0303, 0x01}, + {0x0305, 0x5b}, + {0x0306, 0x01}, + {0x0307, 0x17}, + {0x0323, 0x04}, + {0x0324, 0x01}, + {0x0325, 0x62}, + {0x3012, 0x06}, + {0x3013, 0x02}, + {0x3016, 0x72}, + {0x3021, 0x03}, + {0x3106, 0x21}, + {0x3107, 0xa1}, + {0x3500, 0x00}, + {0x3501, 0x00}, + {0x3502, 0x40}, + {0x3503, 0x88}, + {0x3508, 0x07}, + {0x3509, 0xc0}, + {0x350a, 0x04}, + {0x350b, 0x00}, + {0x350c, 0x07}, + {0x350d, 0xc0}, + {0x350e, 0x04}, + {0x350f, 0x00}, + {0x3510, 0x00}, + {0x3511, 0x00}, + {0x3512, 0x20}, + {0x3624, 0x00}, + {0x3625, 0x4c}, + {0x3660, 0x00}, + {0x3666, 0xa5}, + {0x3667, 0xa5}, + {0x366a, 0x64}, + {0x3673, 0x0d}, + {0x3672, 0x0d}, + {0x3671, 0x0d}, + {0x3670, 0x0d}, + {0x3685, 0x00}, + {0x3694, 0x0d}, + {0x3693, 0x0d}, + {0x3692, 0x0d}, + {0x3691, 0x0d}, + {0x3696, 0x4c}, + {0x3697, 0x4c}, + {0x3698, 0x40}, + {0x3699, 0x80}, + {0x369a, 0x18}, + {0x369b, 0x1f}, + {0x369c, 0x14}, + {0x369d, 0x80}, + {0x369e, 0x40}, + {0x369f, 0x21}, + {0x36a0, 0x12}, + {0x36a1, 0x5d}, + {0x36a2, 0x66}, + {0x370a, 0x00}, + {0x370e, 0x0c}, + {0x3710, 0x00}, + {0x3713, 0x00}, + {0x3725, 0x02}, + {0x372a, 0x03}, + {0x3738, 0xce}, + {0x3748, 0x00}, + {0x374a, 0x00}, + {0x374c, 0x00}, + {0x374e, 0x00}, + {0x3756, 0x00}, + {0x3757, 0x0e}, + {0x3767, 0x00}, + {0x3771, 0x00}, + {0x377b, 0x20}, + {0x377c, 0x00}, + {0x377d, 0x0c}, + {0x3781, 0x03}, + {0x3782, 0x00}, + {0x3789, 0x14}, + {0x3795, 0x02}, + {0x379c, 0x00}, + {0x379d, 0x00}, + {0x37b8, 0x04}, + {0x37ba, 0x03}, + {0x37bb, 0x00}, + {0x37bc, 0x04}, + {0x37be, 0x08}, + {0x37c4, 0x11}, + {0x37c5, 0x80}, + {0x37c6, 0x14}, + {0x37c7, 0x08}, + {0x37da, 0x11}, + {0x381f, 0x08}, + {0x3829, 0x03}, + {0x3881, 0x00}, + {0x3888, 0x04}, + {0x388b, 0x00}, + {0x3c80, 0x10}, + {0x3c86, 0x00}, + {0x3c8c, 0x20}, + {0x3c9f, 0x01}, + {0x3d85, 0x1b}, + {0x3d8c, 0x71}, + {0x3d8d, 0xe2}, + {0x3f00, 0x0b}, + {0x3f06, 0x04}, + {0x400a, 0x01}, + {0x400b, 0x50}, + {0x400e, 0x08}, + {0x4043, 0x7e}, + {0x4045, 0x7e}, + {0x4047, 0x7e}, + {0x4049, 0x7e}, + {0x4090, 0x14}, + {0x40b0, 0x00}, + {0x40b1, 0x00}, + {0x40b2, 0x00}, + {0x40b3, 0x00}, + {0x40b4, 0x00}, + {0x40b5, 0x00}, + {0x40b7, 0x00}, + {0x40b8, 0x00}, + {0x40b9, 0x00}, + {0x40ba, 0x00}, + {0x4301, 0x00}, + {0x4303, 0x00}, + {0x4502, 0x04}, + {0x4503, 0x00}, + {0x4504, 0x06}, + {0x4506, 0x00}, + {0x4507, 0x64}, + {0x4803, 0x00}, + {0x480c, 0x32}, + {0x480e, 0x00}, + {0x4813, 0x00}, + {0x4819, 0x70}, + {0x481f, 0x30}, + {0x4823, 0x3f}, + {0x4825, 0x30}, + {0x4833, 0x10}, + {0x484b, 0x07}, + {0x488b, 0x00}, + {0x4d00, 0x04}, + {0x4d01, 0xad}, + {0x4d02, 0xbc}, + {0x4d03, 0xa1}, + {0x4d04, 0x1f}, + {0x4d05, 0x4c}, + {0x4d0b, 0x01}, + {0x4e00, 0x2a}, + {0x4e0d, 0x00}, + {0x5001, 0x09}, + {0x5004, 0x00}, + {0x5080, 0x04}, + {0x5036, 0x00}, + {0x5180, 0x70}, + {0x5181, 0x10}, + {0x520a, 0x03}, + {0x520b, 0x06}, + {0x520c, 0x0c}, + {0x580b, 0x0f}, + {0x580d, 0x00}, + {0x580f, 0x00}, + {0x5820, 0x00}, + {0x5821, 0x00}, + {0x301c, 0xf8}, + {0x301e, 0xb4}, + {0x301f, 0xd0}, + {0x3022, 0x01}, + {0x3109, 0xe7}, + {0x3600, 0x00}, + {0x3610, 0x65}, + {0x3611, 0x85}, + {0x3613, 0x3a}, + {0x3615, 0x60}, + {0x3621, 0x90}, + {0x3620, 0x0c}, + {0x3629, 0x00}, + {0x3661, 0x04}, + {0x3664, 0x70}, + {0x3665, 0x00}, + {0x3681, 0xa6}, + {0x3682, 0x53}, + {0x3683, 0x2a}, + {0x3684, 0x15}, + {0x3700, 0x2a}, + {0x3701, 0x12}, + {0x3703, 0x28}, + {0x3704, 0x0e}, + {0x3706, 0x4a}, + {0x3709, 0x4a}, + {0x370b, 0xa2}, + {0x370c, 0x01}, + {0x370f, 0x04}, + {0x3714, 0x24}, + {0x3716, 0x04}, + {0x3719, 0x11}, + {0x371a, 0x1e}, + {0x3720, 0x00}, + {0x3724, 0x13}, + {0x373f, 0xb0}, + {0x3741, 0x4a}, + {0x3743, 0x4a}, + {0x3745, 0x4a}, + {0x3747, 0x4a}, + {0x3749, 0xa2}, + {0x374b, 0xa2}, + {0x374d, 0xa2}, + {0x374f, 0xa2}, + {0x3755, 0x10}, + {0x376c, 0x00}, + {0x378d, 0x30}, + {0x3790, 0x4a}, + {0x3791, 0xa2}, + {0x3798, 0x40}, + {0x379e, 0x00}, + {0x379f, 0x04}, + {0x37a1, 0x10}, + {0x37a2, 0x1e}, + {0x37a8, 0x10}, + {0x37a9, 0x1e}, + {0x37ac, 0xa0}, + {0x37b9, 0x01}, + {0x37bd, 0x01}, + {0x37bf, 0x26}, + {0x37c0, 0x11}, + {0x37c2, 0x04}, + {0x37cd, 0x19}, + {0x37e0, 0x08}, + {0x37e6, 0x04}, + {0x37e5, 0x02}, + {0x37e1, 0x0c}, + {0x3737, 0x04}, + {0x37d8, 0x02}, + {0x37e2, 0x10}, + {0x3739, 0x10}, + {0x3662, 0x10}, + {0x37e4, 0x20}, + {0x37e3, 0x08}, + {0x37d9, 0x08}, + {0x4040, 0x00}, + {0x4041, 0x07}, + {0x4008, 0x02}, + {0x4009, 0x0d}, + {0x3800, 0x01}, + {0x3801, 0x80}, + {0x3802, 0x00}, + {0x3803, 0xdc}, + {0x3804, 0x09}, + {0x3805, 0x0f}, + {0x3806, 0x05}, + {0x3807, 0x23}, + {0x3808, 0x07}, + {0x3809, 0x80}, + {0x380a, 0x04}, + {0x380b, 0x38}, + {0x380c, 0x04}, + {0x380d, 0x2e}, + {0x380e, 0x12}, + {0x380f, 0x70}, + {0x3811, 0x08}, + {0x3813, 0x08}, + {0x3814, 0x01}, + {0x3815, 0x01}, + {0x3816, 0x01}, + {0x3817, 0x01}, + {0x3820, 0xB0}, + {0x3821, 0x00}, + {0x3880, 0x25}, + {0x3882, 0x20}, + {0x3c91, 0x0b}, + {0x3c94, 0x45}, + {0x3cad, 0x00}, + {0x3cae, 0x00}, + {0x4000, 0xf3}, + {0x4001, 0x60}, + {0x4003, 0x40}, + {0x4300, 0xff}, + {0x4302, 0x0f}, + {0x4305, 0x83}, + {0x4505, 0x84}, + {0x4809, 0x1e}, + {0x480a, 0x04}, + {0x4837, 0x15}, + {0x4c00, 0x08}, + {0x4c01, 0x08}, + {0x4c04, 0x00}, + {0x4c05, 0x00}, + {0x5000, 0xf9}, + {0x3c8c, 0x10}, +}; diff --git a/system/camerad/sensors/ox03c10.cc b/system/camerad/sensors/ox03c10.cc new file mode 100644 index 0000000000..1f0609820b --- /dev/null +++ b/system/camerad/sensors/ox03c10.cc @@ -0,0 +1,94 @@ +#include "system/camerad/sensors/sensor.h" + +namespace { + +const float sensor_analog_gains_OX03C10[] = { + 1.0, 1.0625, 1.125, 1.1875, 1.25, 1.3125, 1.375, 1.4375, 1.5, 1.5625, 1.6875, + 1.8125, 1.9375, 2.0, 2.125, 2.25, 2.375, 2.5, 2.625, 2.75, 2.875, 3.0, + 3.125, 3.375, 3.625, 3.875, 4.0, 4.25, 4.5, 4.75, 5.0, 5.25, 5.5, + 5.75, 6.0, 6.25, 6.5, 7.0, 7.5, 8.0, 8.5, 9.0, 9.5, 10.0, + 10.5, 11.0, 11.5, 12.0, 12.5, 13.0, 13.5, 14.0, 14.5, 15.0, 15.5}; + +const uint32_t ox03c10_analog_gains_reg[] = { + 0x100, 0x110, 0x120, 0x130, 0x140, 0x150, 0x160, 0x170, 0x180, 0x190, 0x1B0, + 0x1D0, 0x1F0, 0x200, 0x220, 0x240, 0x260, 0x280, 0x2A0, 0x2C0, 0x2E0, 0x300, + 0x320, 0x360, 0x3A0, 0x3E0, 0x400, 0x440, 0x480, 0x4C0, 0x500, 0x540, 0x580, + 0x5C0, 0x600, 0x640, 0x680, 0x700, 0x780, 0x800, 0x880, 0x900, 0x980, 0xA00, + 0xA80, 0xB00, 0xB80, 0xC00, 0xC80, 0xD00, 0xD80, 0xE00, 0xE80, 0xF00, 0xF80}; + +const uint32_t VS_TIME_MIN_OX03C10 = 1; +const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 + +} // namespace + +OX03C10::OX03C10() { + image_sensor = cereal::FrameData::ImageSensor::OX03C10; + data_word = false; + frame_width = FRAME_WIDTH; + frame_height = FRAME_HEIGHT; + frame_stride = FRAME_STRIDE; // (0xa80*12//8) + extra_height = 16; // top 2 + bot 14 + frame_offset = 2; + + start_reg_array.assign(std::begin(start_reg_array_ox03c10), std::end(start_reg_array_ox03c10)); + init_reg_array.assign(std::begin(init_array_ox03c10), std::end(init_array_ox03c10)); + probe_reg_addr = 0x300a; + probe_expected_data = 0x5803; + mipi_format = CAM_FORMAT_MIPI_RAW_12; + frame_data_type = 0x2c; // one is 0x2a, two are 0x2b + mclk_frequency = 24000000; //Hz + + dc_gain_factor = 7.32; + dc_gain_min_weight = 1; // always on is fine + dc_gain_max_weight = 1; + dc_gain_on_grey = 0.9; + dc_gain_off_grey = 1.0; + exposure_time_min = 2; // 1x + exposure_time_max = 2016; + analog_gain_min_idx = 0x0; + analog_gain_rec_idx = 0x0; // 1x + analog_gain_max_idx = 0x36; + analog_gain_cost_delta = -1; + analog_gain_cost_low = 0.4; + analog_gain_cost_high = 6.4; + for (int i = 0; i <= analog_gain_max_idx; i++) { + sensor_analog_gains[i] = sensor_analog_gains_OX03C10[i]; + } + min_ev = (exposure_time_min + VS_TIME_MIN_OX03C10) * sensor_analog_gains[analog_gain_min_idx]; + max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; + target_grey_factor = 0.01; +} + +std::vector OX03C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { + // t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD + uint32_t hcg_time = exposure_time; + uint32_t lcg_time = hcg_time; + uint32_t spd_time = std::min(std::max((uint32_t)exposure_time, (exposure_time_max + VS_TIME_MAX_OX03C10) / 3), exposure_time_max + VS_TIME_MAX_OX03C10); + uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 40, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10); + + uint32_t real_gain = ox03c10_analog_gains_reg[new_exp_g]; + + return { + {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, + {0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF}, + {0x3541, spd_time>>8}, {0x3542, spd_time&0xFF}, + {0x35c2, vs_time&0xFF}, + + {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, + }; +} + +int OX03C10::getSlaveAddress(int port) const { + assert(port >= 0 && port <= 2); + return (int[]){0x6C, 0x20, 0x6C}[port]; +} + +float OX03C10::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { + float score = std::abs(desired_ev - (exp_t * exp_gain)); + float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; + score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; + score += ((1 - analog_gain_cost_delta) + + analog_gain_cost_delta * (exp_g_idx - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * + std::abs(exp_g_idx - gain_idx) * 5.0; + return score; +} diff --git a/system/camerad/cameras/sensor2_i2c.h b/system/camerad/sensors/ox03c10_registers.h similarity index 82% rename from system/camerad/cameras/sensor2_i2c.h rename to system/camerad/sensors/ox03c10_registers.h index 9170c5183a..575a2cb934 100644 --- a/system/camerad/cameras/sensor2_i2c.h +++ b/system/camerad/sensors/ox03c10_registers.h @@ -1,9 +1,9 @@ -struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}}; -struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}}; -struct i2c_random_wr_payload start_reg_array_ox03c10[] = {{0x100, 1}}; -struct i2c_random_wr_payload stop_reg_array_ox03c10[] = {{0x100, 0}}; +#pragma once -struct i2c_random_wr_payload init_array_ox03c10[] = { +const struct i2c_random_wr_payload start_reg_array_ox03c10[] = {{0x100, 1}}; +const struct i2c_random_wr_payload stop_reg_array_ox03c10[] = {{0x100, 0}}; + +const struct i2c_random_wr_payload init_array_ox03c10[] = { {0x103, 1}, {0x107, 1}, @@ -759,118 +759,3 @@ struct i2c_random_wr_payload init_array_ox03c10[] = { {0x3548, 0x0F}, {0x3549, 0x00}, {0x35c1, 0x00}, }; - -struct i2c_random_wr_payload init_array_ar0231[] = { - {0x301A, 0x0018}, // RESET_REGISTER - - // CLOCK Settings - // input clock is 19.2 / 2 * 0x37 = 528 MHz - // pixclk is 528 / 6 = 88 MHz - // full roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*FRAME_LENGTH_LINES)) = 39.99 ms - // img roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*Y_OUTPUT_CONTROL)) = 22.85 ms - {0x302A, 0x0006}, // VT_PIX_CLK_DIV - {0x302C, 0x0001}, // VT_SYS_CLK_DIV - {0x302E, 0x0002}, // PRE_PLL_CLK_DIV - {0x3030, 0x0037}, // PLL_MULTIPLIER - {0x3036, 0x000C}, // OP_PIX_CLK_DIV - {0x3038, 0x0001}, // OP_SYS_CLK_DIV - - // FORMAT - {0x3040, 0xC000}, // READ_MODE - {0x3004, 0x0000}, // X_ADDR_START_ - {0x3008, 0x0787}, // X_ADDR_END_ - {0x3002, 0x0000}, // Y_ADDR_START_ - {0x3006, 0x04B7}, // Y_ADDR_END_ - {0x3032, 0x0000}, // SCALING_MODE - {0x30A2, 0x0001}, // X_ODD_INC_ - {0x30A6, 0x0001}, // Y_ODD_INC_ - {0x3402, 0x0788}, // X_OUTPUT_CONTROL - {0x3404, 0x04B8}, // Y_OUTPUT_CONTROL - {0x3064, 0x1982}, // SMIA_TEST - {0x30BA, 0x11F2}, // DIGITAL_CTRL - - // Enable external trigger and disable GPIO outputs - {0x30CE, 0x0120}, // SLAVE_SH_SYNC_MODE | FRAME_START_MODE - {0x340A, 0xE0}, // GPIO3_INPUT_DISABLE | GPIO2_INPUT_DISABLE | GPIO1_INPUT_DISABLE - {0x340C, 0x802}, // GPIO_HIDRV_EN | GPIO0_ISEL=2 - - // Readout timing - {0x300C, 0x0672}, // LINE_LENGTH_PCK (valid for 3-exposure HDR) - {0x300A, 0x0855}, // FRAME_LENGTH_LINES - {0x3042, 0x0000}, // EXTRA_DELAY - - // Readout Settings - {0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI - {0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12 - {0x3342, 0x1212}, // MIPI_F1_PDT_EDT - {0x3346, 0x1212}, // MIPI_F2_PDT_EDT - {0x334A, 0x1212}, // MIPI_F3_PDT_EDT - {0x334E, 0x1212}, // MIPI_F4_PDT_EDT - {0x3344, 0x0011}, // MIPI_F1_VDT_VC - {0x3348, 0x0111}, // MIPI_F2_VDT_VC - {0x334C, 0x0211}, // MIPI_F3_VDT_VC - {0x3350, 0x0311}, // MIPI_F4_VDT_VC - {0x31B0, 0x0053}, // FRAME_PREAMBLE - {0x31B2, 0x003B}, // LINE_PREAMBLE - {0x301A, 0x001C}, // RESET_REGISTER - - // Noise Corrections - {0x3092, 0x0C24}, // ROW_NOISE_CONTROL - {0x337A, 0x0C80}, // DBLC_SCALE0 - {0x3370, 0x03B1}, // DBLC - {0x3044, 0x0400}, // DARK_CONTROL - - // Enable temperature sensor - {0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG - {0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG - - // Enable dead pixel correction using - // the 1D line correction scheme - {0x31E0, 0x0003}, - - // HDR Settings - {0x3082, 0x0004}, // OPERATION_MODE_CTRL - {0x3238, 0x0444}, // EXPOSURE_RATIO - - {0x1008, 0x0361}, // FINE_INTEGRATION_TIME_MIN - {0x100C, 0x0589}, // FINE_INTEGRATION_TIME2_MIN - {0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN - {0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN - - // TODO: do these have to be lower than LINE_LENGTH_PCK? - {0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_ - {0x321E, 0x0894}, // FINE_INTEGRATION_TIME2 - - {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? - {0x33DA, 0x0000}, // COMPANDING - {0x318E, 0x0200}, // PRE_HDR_GAIN_EN - - // DLO Settings - {0x3100, 0x4000}, // DLO_CONTROL0 - {0x3280, 0x0CCC}, // T1 G1 - {0x3282, 0x0CCC}, // T1 R - {0x3284, 0x0CCC}, // T1 B - {0x3286, 0x0CCC}, // T1 G2 - {0x3288, 0x0FA0}, // T2 G1 - {0x328A, 0x0FA0}, // T2 R - {0x328C, 0x0FA0}, // T2 B - {0x328E, 0x0FA0}, // T2 G2 - - // Initial Gains - {0x3022, 0x0001}, // GROUPED_PARAMETER_HOLD_ - {0x3366, 0xFF77}, // ANALOG_GAIN (1x) - - {0x3060, 0x3333}, // ANALOG_COLOR_GAIN - - {0x3362, 0x0000}, // DC GAIN - - {0x305A, 0x00F8}, // red gain - {0x3058, 0x0122}, // blue gain - {0x3056, 0x009A}, // g1 gain - {0x305C, 0x009A}, // g2 gain - - {0x3022, 0x0000}, // GROUPED_PARAMETER_HOLD_ - - // Initial Integration Time - {0x3012, 0x0005}, -}; diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h new file mode 100644 index 0000000000..4e2194d914 --- /dev/null +++ b/system/camerad/sensors/sensor.h @@ -0,0 +1,93 @@ +#pragma once + +#include +#include +#include +#include +#include +#include "media/cam_sensor.h" +#include "system/camerad/cameras/camera_common.h" +#include "system/camerad/sensors/ar0231_registers.h" +#include "system/camerad/sensors/ox03c10_registers.h" +#include "system/camerad/sensors/os04c10_registers.h" + +#define ANALOG_GAIN_MAX_CNT 55 +const size_t FRAME_WIDTH = 1928; +const size_t FRAME_HEIGHT = 1208; +const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) + + +class SensorInfo { +public: + SensorInfo() = default; + virtual std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { return {}; } + virtual float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const {return 0; } + virtual int getSlaveAddress(int port) const { assert(0); } + virtual void processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const {} + + cereal::FrameData::ImageSensor image_sensor = cereal::FrameData::ImageSensor::UNKNOWN; + uint32_t frame_width, frame_height; + uint32_t frame_stride; + uint32_t frame_offset = 0; + uint32_t extra_height = 0; + int registers_offset = -1; + int stats_offset = -1; + + int exposure_time_min; + int exposure_time_max; + + float dc_gain_factor; + int dc_gain_min_weight; + int dc_gain_max_weight; + float dc_gain_on_grey; + float dc_gain_off_grey; + + float sensor_analog_gains[ANALOG_GAIN_MAX_CNT]; + int analog_gain_min_idx; + int analog_gain_max_idx; + int analog_gain_rec_idx; + int analog_gain_cost_delta; + float analog_gain_cost_low; + float analog_gain_cost_high; + float target_grey_factor; + float min_ev; + float max_ev; + + bool data_word; + uint32_t probe_reg_addr; + uint32_t probe_expected_data; + std::vector start_reg_array; + std::vector init_reg_array; + + uint32_t mipi_format; + uint32_t mclk_frequency; + uint32_t frame_data_type; +}; + +class AR0231 : public SensorInfo { +public: + AR0231(); + std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; + float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; + int getSlaveAddress(int port) const override; + void processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const override; + +private: + mutable std::map> ar0231_register_lut; +}; + +class OX03C10 : public SensorInfo { +public: + OX03C10(); + std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; + float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; + int getSlaveAddress(int port) const override; +}; + +class OS04C10 : public SensorInfo { +public: + OS04C10(); + std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; + float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; + int getSlaveAddress(int port) const override; +}; diff --git a/system/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py index ede97d1a79..8c1b6084c7 100755 --- a/system/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -13,7 +13,6 @@ from openpilot.system.hardware import PC from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert from openpilot.selfdrive.manager.process_config import managed_processes -LM_THRESH = 120 # defined in system/camerad/imgproc/utils.h VISION_STREAMS = { "roadCameraState": VisionStreamType.VISION_STREAM_ROAD, diff --git a/system/hardware/base.h b/system/hardware/base.h index 43f5db023d..dc2282a93a 100644 --- a/system/hardware/base.h +++ b/system/hardware/base.h @@ -29,12 +29,11 @@ public: static void poweroff() {} static void set_brightness(int percent) {} static void set_display_power(bool on) {} - static void set_volume(float volume) {} static bool get_ssh_enabled() { return false; } static void set_ssh_enabled(bool enabled) {} - static void config_cpu_rendering(); + static void config_cpu_rendering(bool offscreen); static bool PC() { return false; } static bool TICI() { return false; } diff --git a/system/hardware/base.py b/system/hardware/base.py index 0b6ca44c3c..7434bb61e8 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -4,7 +4,7 @@ from typing import Dict from cereal import log -ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient', 'pmic']) +ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'pmic']) NetworkType = log.DeviceState.NetworkType @@ -23,6 +23,9 @@ class HardwareBase(ABC): except Exception: return default + def booted(self) -> bool: + return True + @abstractmethod def reboot(self, reason=None): pass @@ -51,10 +54,6 @@ class HardwareBase(ABC): def get_serial(self): pass - @abstractmethod - def get_subscriber_info(self): - pass - @abstractmethod def get_network_info(self): pass diff --git a/system/hardware/hw.h b/system/hardware/hw.h index 2f6ccfffda..394807ccb5 100644 --- a/system/hardware/hw.h +++ b/system/hardware/hw.h @@ -30,13 +30,13 @@ namespace Path { } inline std::string params() { - return Hardware::PC() ? util::getenv("PARAMS_ROOT", Path::comma_home() + "/params") : "/data/params"; + return util::getenv("PARAMS_ROOT", Hardware::PC() ? (Path::comma_home() + "/params") : "/data/params"); } inline std::string rsa_file() { return Hardware::PC() ? Path::comma_home() + "/persist/comma/id_rsa" : "/persist/comma/id_rsa"; } - + inline std::string swaglog_ipc() { return "ipc:///tmp/logmessage" + Path::openpilot_prefix(); } diff --git a/system/hardware/hw.py b/system/hardware/hw.py index 119ca48c86..694299d72e 100644 --- a/system/hardware/hw.py +++ b/system/hardware/hw.py @@ -3,6 +3,8 @@ from pathlib import Path from openpilot.system.hardware import PC +DEFAULT_DOWNLOAD_CACHE_ROOT = "/tmp/comma_download_cache" + class Paths: @staticmethod def comma_home() -> str: @@ -31,5 +33,26 @@ class Paths: @staticmethod def download_cache_root() -> str: if os.environ.get('COMMA_CACHE', False): - return os.environ['COMMA_CACHE'] - return "/tmp/comma_download_cache" + os.environ.get("OPENPILOT_PREFIX", "") + "/" + return os.environ['COMMA_CACHE'] + "/" + return DEFAULT_DOWNLOAD_CACHE_ROOT + os.environ.get("OPENPILOT_PREFIX", "") + "/" + + @staticmethod + def persist_root() -> str: + if PC: + return os.path.join(Paths.comma_home(), "persist") + else: + return "/persist/" + + @staticmethod + def stats_root() -> str: + if PC: + return str(Path(Paths.comma_home()) / "stats") + else: + return "/data/stats/" + + @staticmethod + def config_root() -> str: + if PC: + return Paths.comma_home() + else: + return "/tmp/.comma" diff --git a/system/hardware/pc/hardware.h b/system/hardware/pc/hardware.h index 7a7ddd60b7..5dea184ca6 100644 --- a/system/hardware/pc/hardware.h +++ b/system/hardware/pc/hardware.h @@ -13,16 +13,10 @@ public: static bool TICI() { return util::getenv("TICI", 0) == 1; } static bool AGNOS() { return util::getenv("TICI", 0) == 1; } - static void set_volume(float volume) { - volume = util::map_val(volume, 0.f, 1.f, MIN_VOLUME, MAX_VOLUME); - - char volume_str[6]; - snprintf(volume_str, sizeof(volume_str), "%.3f", volume); - std::system(("pactl set-sink-volume @DEFAULT_SINK@ " + std::string(volume_str)).c_str()); - } - - static void config_cpu_rendering() { - setenv("QT_QPA_PLATFORM", "offscreen", 1); + static void config_cpu_rendering(bool offscreen) { + if (offscreen) { + setenv("QT_QPA_PLATFORM", "offscreen", 1); + } setenv("__GLX_VENDOR_LIBRARY_NAME", "mesa", 1); setenv("LP_NUM_THREADS", "0", 1); // disable threading so we stay on our assigned CPU } diff --git a/system/hardware/pc/hardware.py b/system/hardware/pc/hardware.py index 27c05f5904..719e272aea 100644 --- a/system/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -29,9 +29,6 @@ class Pc(HardwareBase): def get_serial(self): return "cccccccc" - def get_subscriber_info(self): - return "" - def get_network_info(self): return None @@ -60,7 +57,7 @@ class Pc(HardwareBase): print("SHUTDOWN!") def get_thermal_config(self): - return ThermalConfig(cpu=((None,), 1), gpu=((None,), 1), mem=(None, 1), bat=(None, 1), ambient=(None, 1), pmic=((None,), 1)) + return ThermalConfig(cpu=((None,), 1), gpu=((None,), 1), mem=(None, 1), bat=(None, 1), pmic=((None,), 1)) def set_screen_brightness(self, percentage): pass diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index 7e8cd480be..e69842cfec 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -1,9 +1,9 @@ [ { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-8d8d8620de8b2687f3a8fffdb81b2abd1fe2ead5bc831361a1a212e5589ac279.img.xz", - "hash": "8d8d8620de8b2687f3a8fffdb81b2abd1fe2ead5bc831361a1a212e5589ac279", - "hash_raw": "8d8d8620de8b2687f3a8fffdb81b2abd1fe2ead5bc831361a1a212e5589ac279", + "url": "https://commadist.azureedge.net/agnosupdate/boot-f0de74e139b8b99224738d4e72a5b1831758f20b09ff6bb28f3aaaae1c4c1ebe.img.xz", + "hash": "f0de74e139b8b99224738d4e72a5b1831758f20b09ff6bb28f3aaaae1c4c1ebe", + "hash_raw": "f0de74e139b8b99224738d4e72a5b1831758f20b09ff6bb28f3aaaae1c4c1ebe", "size": 15636480, "sparse": false, "full_check": true, @@ -11,9 +11,9 @@ }, { "name": "abl", - "url": "https://commadist.azureedge.net/agnosupdate/abl-0084fcf79fea067632a1c2d9519b6445ad484aa8b09f49f22e6b45b4dccacd2d.img.xz", - "hash": "0084fcf79fea067632a1c2d9519b6445ad484aa8b09f49f22e6b45b4dccacd2d", - "hash_raw": "0084fcf79fea067632a1c2d9519b6445ad484aa8b09f49f22e6b45b4dccacd2d", + "url": "https://commadist.azureedge.net/agnosupdate/abl-eeb89a74c968a5a2ffce96f23158b72e03e2814adf72ef59d1200ba8ea5d2f39.img.xz", + "hash": "eeb89a74c968a5a2ffce96f23158b72e03e2814adf72ef59d1200ba8ea5d2f39", + "hash_raw": "eeb89a74c968a5a2ffce96f23158b72e03e2814adf72ef59d1200ba8ea5d2f39", "size": 274432, "sparse": false, "full_check": true, @@ -21,9 +21,9 @@ }, { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-942b9b2914d89c2a70fdf27380b59e04b549ac2fd53ecb29d6549d1a9c8daeaa.img.xz", - "hash": "942b9b2914d89c2a70fdf27380b59e04b549ac2fd53ecb29d6549d1a9c8daeaa", - "hash_raw": "942b9b2914d89c2a70fdf27380b59e04b549ac2fd53ecb29d6549d1a9c8daeaa", + "url": "https://commadist.azureedge.net/agnosupdate/xbl-bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5.img.xz", + "hash": "bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5", + "hash_raw": "bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5", "size": 3282672, "sparse": false, "full_check": true, @@ -31,9 +31,9 @@ }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-6881d94599f65d94c13bcc0bd860184dfba2dfe96ec776d08fb35ac5b5f85bbf.img.xz", - "hash": "6881d94599f65d94c13bcc0bd860184dfba2dfe96ec776d08fb35ac5b5f85bbf", - "hash_raw": "6881d94599f65d94c13bcc0bd860184dfba2dfe96ec776d08fb35ac5b5f85bbf", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac.img.xz", + "hash": "19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac", + "hash_raw": "19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac", "size": 98124, "sparse": false, "full_check": true, @@ -41,9 +41,9 @@ }, { "name": "devcfg", - "url": "https://commadist.azureedge.net/agnosupdate/devcfg-9bbf168baff6101f4890c5c95c118e30813c2610cfb35b8e19e363f04a32a262.img.xz", - "hash": "9bbf168baff6101f4890c5c95c118e30813c2610cfb35b8e19e363f04a32a262", - "hash_raw": "9bbf168baff6101f4890c5c95c118e30813c2610cfb35b8e19e363f04a32a262", + "url": "https://commadist.azureedge.net/agnosupdate/devcfg-be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27.img.xz", + "hash": "be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27", + "hash_raw": "be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27", "size": 40336, "sparse": false, "full_check": true, @@ -51,9 +51,9 @@ }, { "name": "aop", - "url": "https://commadist.azureedge.net/agnosupdate/aop-c1d9d712980f6b2a4b12196597f4d1bf3fe4fec6c59edf29ae63ef21f11b8222.img.xz", - "hash": "c1d9d712980f6b2a4b12196597f4d1bf3fe4fec6c59edf29ae63ef21f11b8222", - "hash_raw": "c1d9d712980f6b2a4b12196597f4d1bf3fe4fec6c59edf29ae63ef21f11b8222", + "url": "https://commadist.azureedge.net/agnosupdate/aop-5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f.img.xz", + "hash": "5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f", + "hash_raw": "5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f", "size": 184364, "sparse": false, "full_check": true, @@ -61,16 +61,17 @@ }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-e1fa3018bce9bad01c6967e5e21f1141cf5c8f02d2edfaed51c738f74a32a432.img.xz", - "hash": "611011f3e3f147bc24f371105a9dd3760ec11ba424c56d4a442a66b098c784c0", - "hash_raw": "e1fa3018bce9bad01c6967e5e21f1141cf5c8f02d2edfaed51c738f74a32a432", + "url": "https://commadist.azureedge.net/agnosupdate/system-0f69173d5f3058f7197c139442a6556be59e52f15402a263215a329ba5ec41e2.img.xz", + "hash": "4858385ba6284bcaa179ab77ac4263486e4d8670df921e4ac400464dc1dde59c", + "hash_raw": "0f69173d5f3058f7197c139442a6556be59e52f15402a263215a329ba5ec41e2", "size": 10737418240, "sparse": true, "full_check": false, "has_ab": true, "alt": { - "hash": "256442a55fcb9e8f72969f003a4db91598dee1136f8dda85b553a557d36b93d8", - "url": "https://commadist.azureedge.net/agnosupdate/system-skip-chunks-e1fa3018bce9bad01c6967e5e21f1141cf5c8f02d2edfaed51c738f74a32a432.img.xz" + "hash": "42658a6fff660d9b6abb9cb9fbb3481071259c9a9598718af6b1edff2b556009", + "url": "https://commadist.azureedge.net/agnosupdate/system-skip-chunks-0f69173d5f3058f7197c139442a6556be59e52f15402a263215a329ba5ec41e2.img.xz", + "size": 4548292756 } } -] +] \ No newline at end of file diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index ef7d9adb79..342281b0f8 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -20,7 +20,7 @@ class StreamingDecompressor: def __init__(self, url: str) -> None: self.buf = b"" - self.req = requests.get(url, stream=True, headers={'Accept-Encoding': None}, timeout=60) # type: ignore + self.req = requests.get(url, stream=True, headers={'Accept-Encoding': None}, timeout=60) self.it = self.req.iter_content(chunk_size=1024 * 1024) self.decompressor = lzma.LZMADecompressor(format=lzma.FORMAT_AUTO) self.eof = False diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h index fe0a20ae58..e553a665a8 100644 --- a/system/hardware/tici/hardware.h +++ b/system/hardware/tici/hardware.h @@ -67,19 +67,12 @@ public: bl_power_control.close(); } } - static void set_volume(float volume) { - volume = util::map_val(volume, 0.f, 1.f, MIN_VOLUME, MAX_VOLUME); - - char volume_str[6]; - snprintf(volume_str, sizeof(volume_str), "%.3f", volume); - std::system(("pactl set-sink-volume @DEFAULT_SINK@ " + std::string(volume_str)).c_str()); - } - static std::map get_init_logs() { std::map ret = { {"/BUILD", util::read_file("/BUILD")}, {"lsblk", util::check_output("lsblk -o NAME,SIZE,STATE,VENDOR,MODEL,REV,SERIAL")}, + {"SOM ID", util::read_file("/sys/devices/platform/vendor/vendor:gpio-som-id/som_id")}, }; std::string bs = util::check_output("abctl --boot_slot"); @@ -104,8 +97,10 @@ public: static bool get_ssh_enabled() { return Params().getBool("SshEnabled"); } static void set_ssh_enabled(bool enabled) { Params().putBool("SshEnabled", enabled); } - static void config_cpu_rendering() { - setenv("QT_QPA_PLATFORM", "eglfs", 1); // offscreen doesn't work with EGL/GLES + static void config_cpu_rendering(bool offscreen) { + if (offscreen) { + setenv("QT_QPA_PLATFORM", "eglfs", 1); // offscreen doesn't work with EGL/GLES + } setenv("LP_NUM_THREADS", "0", 1); // disable threading so we stay on our assigned CPU } }; diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 5f8267a461..5bb1032ba9 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -74,6 +74,11 @@ def sudo_write(val, path): # fallback for debugfs files os.system(f"sudo su -c 'echo {val} > {path}'") +def sudo_read(path: str) -> str: + try: + return subprocess.check_output(f"sudo cat {path}", shell=True, encoding='utf8') + except Exception: + return "" def affine_irq(val, action): irqs = get_irqs_for_action(action) @@ -201,9 +206,6 @@ class Tici(HardwareBase): 'data_connected': modem.Get(MM_MODEM, 'State', dbus_interface=DBUS_PROPS, timeout=TIMEOUT) == MM_MODEM_STATE.CONNECTED, } - def get_subscriber_info(self): - return "" - def get_imei(self, slot): if slot != 0: return "" @@ -293,67 +295,6 @@ class Tici(HardwareBase): return super().get_network_metered(network_type) - @staticmethod - def set_bandwidth_limit(upload_speed_kbps: int, download_speed_kbps: int) -> None: - upload_speed_kbps = int(upload_speed_kbps) # Ensure integer value - download_speed_kbps = int(download_speed_kbps) # Ensure integer value - - adapter = "wwan0" - ifb = "ifb0" - - sudo = ["sudo"] - tc = sudo + ["tc"] - - # check, cmd - cleanup = [ - # Clean up old rules - (False, tc + ["qdisc", "del", "dev", adapter, "root"]), - (False, tc + ["qdisc", "del", "dev", ifb, "root"]), - (False, tc + ["qdisc", "del", "dev", adapter, "ingress"]), - (False, tc + ["qdisc", "del", "dev", ifb, "ingress"]), - - # Bring ifb0 down - (False, sudo + ["ip", "link", "set", "dev", ifb, "down"]), - ] - - upload = [ - # Create root Hierarchy Token Bucket that sends all traffic to 1:20 - (True, tc + ["qdisc", "add", "dev", adapter, "root", "handle", "1:", "htb", "default", "20"]), - - # Create class 1:20 with specified rate limit - (True, tc + ["class", "add", "dev", adapter, "parent", "1:", "classid", "1:20", "htb", "rate", f"{upload_speed_kbps}kbit"]), - - # Create universal 32 bit filter on adapter that sends all outbound ip traffic through the class - (True, tc + ["filter", "add", "dev", adapter, "parent", "1:", "protocol", "ip", "prio", \ - "10", "u32", "match", "ip", "dst", "0.0.0.0/0", "flowid", "1:20"]), - ] - - download = [ - # Bring ifb0 up - (True, sudo + ["ip", "link", "set", "dev", ifb, "up"]), - - # Redirect ingress (incoming) to egress ifb0 - (True, tc + ["qdisc", "add", "dev", adapter, "handle", "ffff:", "ingress"]), - (True, tc + ["filter", "add", "dev", adapter, "parent", "ffff:", "protocol", "ip", "u32", \ - "match", "u32", "0", "0", "action", "mirred", "egress", "redirect", "dev", ifb]), - - # Add class and rules for virtual interface - (True, tc + ["qdisc", "add", "dev", ifb, "root", "handle", "2:", "htb"]), - (True, tc + ["class", "add", "dev", ifb, "parent", "2:", "classid", "2:1", "htb", "rate", f"{download_speed_kbps}kbit"]), - - # Add filter to rule for IP address - (True, tc + ["filter", "add", "dev", ifb, "protocol", "ip", "parent", "2:", "prio", "1", "u32", "match", "ip", "src", "0.0.0.0/0", "flowid", "2:1"]), - ] - - commands = cleanup - if upload_speed_kbps != -1: - commands += upload - if download_speed_kbps != -1: - commands += download - - for check, cmd in commands: - subprocess.run(cmd, check=check) - def get_modem_version(self): try: modem = self.get_modem() @@ -393,10 +334,6 @@ class Tici(HardwareBase): pass return ret - def get_usb_present(self): - # Not sure if relevant on tici, but the file exists - return self.read_param_file("/sys/class/power_supply/usb/present", lambda x: bool(int(x)), False) - def get_current_power_draw(self): return (self.read_param_file("/sys/class/hwmon/hwmon1/power1_input", int) / 1e6) @@ -412,7 +349,6 @@ class Tici(HardwareBase): gpu=(("gpu0-usr", "gpu1-usr"), 1000), mem=("ddr-usr", 1000), bat=(None, 1), - ambient=("xo-therm-adc", 1000), pmic=(("pm8998_tz", "pm8005_tz"), 1000)) def set_screen_brightness(self, percentage): @@ -520,24 +456,37 @@ class Tici(HardwareBase): def configure_modem(self): sim_id = self.get_sim_info().get('sim_id', '') - # configure modem as data-centric - cmds = [ - 'AT+QNVW=5280,0,"0102000000000000"', - 'AT+QNVFW="/nv/item_files/ims/IMS_enable",00', - 'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01', - ] modem = self.get_modem() + try: + manufacturer = str(modem.Get(MM_MODEM, 'Manufacturer', dbus_interface=DBUS_PROPS, timeout=TIMEOUT)) + except Exception: + manufacturer = None + + cmds = [] + if manufacturer == 'Cavli Inc.': + cmds += [ + # use sim slot + 'AT^SIMSWAP=1', + + # configure ECM mode + 'AT$QCPCFG=usbNet,1' + ] + else: + cmds += [ + # configure modem as data-centric + 'AT+QNVW=5280,0,"0102000000000000"', + 'AT+QNVFW="/nv/item_files/ims/IMS_enable",00', + 'AT+QNVFW="/nv/item_files/modem/mmode/ue_usage_setting",01', + ] + + # clear out old blue prime initial APN + os.system('mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn="') for cmd in cmds: try: modem.Command(cmd, math.ceil(TIMEOUT), dbus_interface=MM_MODEM, timeout=TIMEOUT) except Exception: pass - # blue prime - blue_prime = sim_id.startswith('8901410') - initial_apn = "Broadband" if blue_prime else "" - os.system(f'mmcli -m any --3gpp-set-initial-eps-bearer-settings="apn={initial_apn}"') - # eSIM prime if sim_id.startswith('8985235'): dest = "/etc/NetworkManager/system-connections/esim.nmconnection" @@ -615,6 +564,12 @@ class Tici(HardwareBase): time.sleep(0.5) gpio_set(GPIO.STM_BOOT0, 0) + def booted(self): + # this normally boots within 8s, but on rare occasions takes 30+s + encoder_state = sudo_read("/sys/kernel/debug/msm_vidc/core0/info") + if "Core state: 0" in encoder_state and (time.monotonic() < 60*2): + return False + return True if __name__ == "__main__": t = Tici() diff --git a/system/loggerd/bootlog.cc b/system/loggerd/bootlog.cc index 771594d20c..b8257b6d69 100644 --- a/system/loggerd/bootlog.cc +++ b/system/loggerd/bootlog.cc @@ -49,8 +49,8 @@ static kj::Array build_boot_log() { } int main(int argc, char** argv) { - const std::string timestr = logger_get_route_name(); - const std::string path = Path::log_root() + "/boot/" + timestr; + const std::string id = logger_get_identifier("BootCount"); + const std::string path = Path::log_root() + "/boot/" + id; LOGW("bootlog to %s", path.c_str()); // Open bootlog @@ -64,7 +64,7 @@ int main(int argc, char** argv) { file.write(build_boot_log().asBytes()); // Write out bootlog param to match routes with bootlog - Params().put("CurrentBootlog", timestr.c_str()); + Params().put("CurrentBootlog", id.c_str()); return 0; } diff --git a/system/loggerd/config.py b/system/loggerd/config.py index 664e78b378..5c2c89b73f 100644 --- a/system/loggerd/config.py +++ b/system/loggerd/config.py @@ -1,6 +1,4 @@ import os -from pathlib import Path -from openpilot.system.hardware import PC from openpilot.system.hardware.hw import Paths @@ -9,10 +7,6 @@ SEGMENT_LENGTH = 60 STATS_DIR_FILE_LIMIT = 10000 STATS_SOCKET = "ipc:///tmp/stats" -if PC: - STATS_DIR = str(Path.home() / ".comma" / "stats") -else: - STATS_DIR = "/data/stats/" STATS_FLUSH_TIME_S = 60 def get_available_percent(default=None): diff --git a/system/loggerd/deleter.py b/system/loggerd/deleter.py index b060232b6e..868340150a 100755 --- a/system/loggerd/deleter.py +++ b/system/loggerd/deleter.py @@ -4,7 +4,7 @@ import shutil import threading from typing import List from openpilot.system.hardware.hw import Paths -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.system.loggerd.config import get_available_bytes, get_available_percent from openpilot.system.loggerd.uploader import listdir_by_creation from openpilot.system.loggerd.xattr_cache import getxattr diff --git a/system/loggerd/encoder/encoder.cc b/system/loggerd/encoder/encoder.cc index 869b4617b3..c4bd91bcf7 100644 --- a/system/loggerd/encoder/encoder.cc +++ b/system/loggerd/encoder/encoder.cc @@ -2,6 +2,10 @@ VideoEncoder::VideoEncoder(const EncoderInfo &encoder_info, int in_width, int in_height) : encoder_info(encoder_info), in_width(in_width), in_height(in_height) { + + out_width = encoder_info.frame_width > 0 ? encoder_info.frame_width : in_width; + out_height = encoder_info.frame_height > 0 ? encoder_info.frame_height : in_height; + pm.reset(new PubMaster({encoder_info.publish_name})); } @@ -25,10 +29,15 @@ void VideoEncoder::publisher_publish(VideoEncoder *e, int segment_num, uint32_t edata.setFlags(flags); edata.setLen(dat.size()); edat.setData(dat); + edat.setWidth(out_width); + edat.setHeight(out_height); if (flags & V4L2_BUF_FLAG_KEYFRAME) edat.setHeader(header); - auto words = new kj::Array(capnp::messageToFlatArray(msg)); - auto bytes = words->asBytes(); - e->pm->send(e->encoder_info.publish_name, bytes.begin(), bytes.size()); - delete words; + uint32_t bytes_size = capnp::computeSerializedSizeInWords(msg) * sizeof(capnp::word); + if (e->msg_cache.size() < bytes_size) { + e->msg_cache.resize(bytes_size); + } + kj::ArrayOutputStream output_stream(kj::ArrayPtr(e->msg_cache.data(), bytes_size)); + capnp::writeMessage(output_stream, msg); + e->pm->send(e->encoder_info.publish_name, e->msg_cache.data(), bytes_size); } diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h index a8bfd5c054..7c203f9193 100644 --- a/system/loggerd/encoder/encoder.h +++ b/system/loggerd/encoder/encoder.h @@ -4,6 +4,7 @@ #include #include #include +#include #include "cereal/messaging/messaging.h" #include "cereal/visionipc/visionipc.h" @@ -21,15 +22,16 @@ public: virtual void encoder_open(const char* path) = 0; virtual void encoder_close() = 0; - static void publisher_publish(VideoEncoder *e, int segment_num, uint32_t idx, VisionIpcBufExtra &extra, unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat); - + void publisher_publish(VideoEncoder *e, int segment_num, uint32_t idx, VisionIpcBufExtra &extra, unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat); protected: int in_width, in_height; + int out_width, out_height; const EncoderInfo encoder_info; private: // total frames encoded int cnt = 0; std::unique_ptr pm; + std::vector msg_cache; }; diff --git a/system/loggerd/encoder/ffmpeg_encoder.cc b/system/loggerd/encoder/ffmpeg_encoder.cc index f44f2fbed7..9d992f088d 100644 --- a/system/loggerd/encoder/ffmpeg_encoder.cc +++ b/system/loggerd/encoder/ffmpeg_encoder.cc @@ -29,16 +29,16 @@ FfmpegEncoder::FfmpegEncoder(const EncoderInfo &encoder_info, int in_width, int frame = av_frame_alloc(); assert(frame); frame->format = AV_PIX_FMT_YUV420P; - frame->width = encoder_info.frame_width; - frame->height = encoder_info.frame_height; - frame->linesize[0] = encoder_info.frame_width; - frame->linesize[1] = encoder_info.frame_width/2; - frame->linesize[2] = encoder_info.frame_width/2; + frame->width = out_width; + frame->height = out_height; + frame->linesize[0] = out_width; + frame->linesize[1] = out_width/2; + frame->linesize[2] = out_width/2; convert_buf.resize(in_width * in_height * 3 / 2); - if (in_width != encoder_info.frame_width || in_height != encoder_info.frame_height) { - downscale_buf.resize(encoder_info.frame_width * encoder_info.frame_height * 3 / 2); + if (in_width != out_width || in_height != out_height) { + downscale_buf.resize(out_width * out_height * 3 / 2); } } diff --git a/system/loggerd/encoder/v4l_encoder.cc b/system/loggerd/encoder/v4l_encoder.cc index 571f5979e2..2bd2863126 100644 --- a/system/loggerd/encoder/v4l_encoder.cc +++ b/system/loggerd/encoder/v4l_encoder.cc @@ -164,8 +164,8 @@ V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_hei .fmt = { .pix_mp = { // downscales are free with v4l - .width = (unsigned int)encoder_info.frame_width, - .height = (unsigned int)encoder_info.frame_height, + .width = (unsigned int)(out_width), + .height = (unsigned int)(out_height), .pixelformat = (encoder_info.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C) ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, .field = V4L2_FIELD_ANY, .colorspace = V4L2_COLORSPACE_DEFAULT, diff --git a/system/loggerd/logger.cc b/system/loggerd/logger.cc index 1474552a13..7a829a2f1f 100644 --- a/system/loggerd/logger.cc +++ b/system/loggerd/logger.cc @@ -1,22 +1,11 @@ #include "system/loggerd/logger.h" -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include #include -#include #include -#include -#include #include +#include +#include +#include #include "common/params.h" #include "common/swaglog.h" @@ -51,13 +40,14 @@ kj::Array logger_build_init_data() { init.setOsVersion(util::read_file("/VERSION")); // log params - auto params = Params(); + auto params = Params(util::getenv("PARAMS_COPY_PATH", "")); std::map params_map = params.readAll(); init.setGitCommit(params_map["GitCommit"]); + init.setGitCommitDate(params_map["GitCommitDate"]); init.setGitBranch(params_map["GitBranch"]); init.setGitRemote(params_map["GitRemote"]); - init.setPassive(params.getBool("Passive")); + init.setPassive(false); init.setDongleId(params_map["DongleId"]); auto lparams = init.initParams().initEntries(params_map.size()); @@ -108,159 +98,75 @@ std::string logger_get_route_name() { return route_name; } -void log_init_data(LoggerState *s) { - auto bytes = s->init_data.asBytes(); - logger_log(s, bytes.begin(), bytes.size(), s->has_qlog); -} +std::string logger_get_identifier(std::string key) { + // a log identifier is a 32 bit counter, plus a 10 character unique ID. + // e.g. 000001a3--c20ba54385 + + Params params; + uint32_t cnt; + try { + cnt = std::stol(params.get(key)); + } catch (std::exception &e) { + cnt = 0; + } + params.put(key, std::to_string(cnt + 1)); + std::stringstream ss; + std::random_device rd; + std::mt19937 mt(rd()); + std::uniform_int_distribution dist(0, 15); + for (int i = 0; i < 10; ++i) { + ss << std::hex << dist(mt); + } + + return util::string_format("%08x--%s", cnt, ss.str().c_str()); +} -static void lh_log_sentinel(LoggerHandle *h, SentinelType type) { +static void log_sentinel(LoggerState *log, SentinelType type, int eixt_signal = 0) { MessageBuilder msg; auto sen = msg.initEvent().initSentinel(); sen.setType(type); - sen.setSignal(h->exit_signal); - auto bytes = msg.toBytes(); - - lh_log(h, bytes.begin(), bytes.size(), true); + sen.setSignal(eixt_signal); + log->write(msg.toBytes(), true); } -// ***** logging functions ***** - -void logger_init(LoggerState *s, bool has_qlog) { - pthread_mutex_init(&s->lock, NULL); - - s->part = -1; - s->has_qlog = has_qlog; - s->route_name = logger_get_route_name(); - s->init_data = logger_build_init_data(); +LoggerState::LoggerState(const std::string &log_root) { + route_name = logger_get_route_name(); + route_path = log_root + "/" + route_name; + init_data = logger_build_init_data(); } -static LoggerHandle* logger_open(LoggerState *s, const char* root_path) { - LoggerHandle *h = NULL; - for (int i=0; ihandles[i].refcnt == 0) { - h = &s->handles[i]; - break; - } +LoggerState::~LoggerState() { + if (rlog) { + log_sentinel(this, SentinelType::END_OF_ROUTE, exit_signal); + std::remove(lock_file.c_str()); } - assert(h); - - snprintf(h->segment_path, sizeof(h->segment_path), - "%s/%s--%d", root_path, s->route_name.c_str(), s->part); - - snprintf(h->log_path, sizeof(h->log_path), "%s/rlog", h->segment_path); - snprintf(h->qlog_path, sizeof(h->qlog_path), "%s/qlog", h->segment_path); - snprintf(h->lock_path, sizeof(h->lock_path), "%s.lock", h->log_path); - h->end_sentinel_type = SentinelType::END_OF_SEGMENT; - h->exit_signal = 0; - - if (!util::create_directories(h->segment_path, 0775)) return nullptr; - - FILE* lock_file = fopen(h->lock_path, "wb"); - if (lock_file == NULL) return NULL; - fclose(lock_file); - - h->log = std::make_unique(h->log_path); - if (s->has_qlog) { - h->q_log = std::make_unique(h->qlog_path); - } - - pthread_mutex_init(&h->lock, NULL); - h->refcnt++; - return h; } -int logger_next(LoggerState *s, const char* root_path, - char* out_segment_path, size_t out_segment_path_len, - int* out_part) { - bool is_start_of_route = !s->cur_handle; - - pthread_mutex_lock(&s->lock); - s->part++; - - LoggerHandle* next_h = logger_open(s, root_path); - if (!next_h) { - pthread_mutex_unlock(&s->lock); - return -1; +bool LoggerState::next() { + if (rlog) { + log_sentinel(this, SentinelType::END_OF_SEGMENT); + std::remove(lock_file.c_str()); } - if (s->cur_handle) { - lh_close(s->cur_handle); - } - s->cur_handle = next_h; - - if (out_segment_path) { - snprintf(out_segment_path, out_segment_path_len, "%s", next_h->segment_path); - } - if (out_part) { - *out_part = s->part; - } + segment_path = route_path + "--" + std::to_string(++part); + bool ret = util::create_directories(segment_path, 0775); + assert(ret == true); - pthread_mutex_unlock(&s->lock); + const std::string rlog_path = segment_path + "/rlog"; + lock_file = rlog_path + ".lock"; + std::ofstream{lock_file}; - // write beginning of log metadata - log_init_data(s); - lh_log_sentinel(s->cur_handle, is_start_of_route ? SentinelType::START_OF_ROUTE : SentinelType::START_OF_SEGMENT); - return 0; -} + rlog.reset(new RawFile(rlog_path)); + qlog.reset(new RawFile(segment_path + "/qlog")); -LoggerHandle* logger_get_handle(LoggerState *s) { - pthread_mutex_lock(&s->lock); - LoggerHandle* h = s->cur_handle; - if (h) { - pthread_mutex_lock(&h->lock); - h->refcnt++; - pthread_mutex_unlock(&h->lock); - } - pthread_mutex_unlock(&s->lock); - return h; + // log init data & sentinel type. + write(init_data.asBytes(), true); + log_sentinel(this, part > 0 ? SentinelType::START_OF_SEGMENT : SentinelType::START_OF_ROUTE); + return true; } -void logger_log(LoggerState *s, uint8_t* data, size_t data_size, bool in_qlog) { - pthread_mutex_lock(&s->lock); - if (s->cur_handle) { - lh_log(s->cur_handle, data, data_size, in_qlog); - } - pthread_mutex_unlock(&s->lock); -} - -void logger_close(LoggerState *s, ExitHandler *exit_handler) { - pthread_mutex_lock(&s->lock); - if (s->cur_handle) { - s->cur_handle->exit_signal = exit_handler && exit_handler->signal.load(); - s->cur_handle->end_sentinel_type = SentinelType::END_OF_ROUTE; - lh_close(s->cur_handle); - } - pthread_mutex_unlock(&s->lock); -} - -void lh_log(LoggerHandle* h, uint8_t* data, size_t data_size, bool in_qlog) { - pthread_mutex_lock(&h->lock); - assert(h->refcnt > 0); - h->log->write(data, data_size); - if (in_qlog && h->q_log) { - h->q_log->write(data, data_size); - } - pthread_mutex_unlock(&h->lock); -} - -void lh_close(LoggerHandle* h) { - pthread_mutex_lock(&h->lock); - assert(h->refcnt > 0); - if (h->refcnt == 1) { - // a very ugly hack. only here can guarantee sentinel is the last msg - pthread_mutex_unlock(&h->lock); - lh_log_sentinel(h, h->end_sentinel_type); - pthread_mutex_lock(&h->lock); - } - h->refcnt--; - if (h->refcnt == 0) { - h->log.reset(nullptr); - h->q_log.reset(nullptr); - unlink(h->lock_path); - pthread_mutex_unlock(&h->lock); - pthread_mutex_destroy(&h->lock); - return; - } - pthread_mutex_unlock(&h->lock); +void LoggerState::write(uint8_t* data, size_t size, bool in_qlog) { + rlog->write(data, size); + if (in_qlog) qlog->write(data, size); } diff --git a/system/loggerd/logger.h b/system/loggerd/logger.h index 06b11e72f9..dd3bee150c 100644 --- a/system/loggerd/logger.h +++ b/system/loggerd/logger.h @@ -1,27 +1,17 @@ #pragma once -#include - #include -#include -#include #include #include -#include -#include - #include "cereal/messaging/messaging.h" #include "common/util.h" -#include "common/swaglog.h" #include "system/hardware/hw.h" -#define LOGGER_MAX_HANDLES 16 - class RawFile { public: - RawFile(const char* path) { - file = util::safe_fopen(path, "wb"); + RawFile(const std::string &path) { + file = util::safe_fopen(path.c_str(), "wb"); assert(file != nullptr); } ~RawFile() { @@ -41,39 +31,26 @@ class RawFile { typedef cereal::Sentinel::SentinelType SentinelType; -typedef struct LoggerHandle { - pthread_mutex_t lock; - SentinelType end_sentinel_type; - int exit_signal; - int refcnt; - char segment_path[4096]; - char log_path[4096]; - char qlog_path[4096]; - char lock_path[4096]; - std::unique_ptr log, q_log; -} LoggerHandle; -typedef struct LoggerState { - pthread_mutex_t lock; - int part; +class LoggerState { +public: + LoggerState(const std::string& log_root = Path::log_root()); + ~LoggerState(); + bool next(); + void write(uint8_t* data, size_t size, bool in_qlog); + inline int segment() const { return part; } + inline const std::string& segmentPath() const { return segment_path; } + inline const std::string& routeName() const { return route_name; } + inline void write(kj::ArrayPtr bytes, bool in_qlog) { write(bytes.begin(), bytes.size(), in_qlog); } + inline void setExitSignal(int signal) { exit_signal = signal; } + +protected: + int part = -1, exit_signal = 0; + std::string route_path, route_name, segment_path, lock_file; kj::Array init_data; - std::string route_name; - char log_name[64]; - bool has_qlog; - - LoggerHandle handles[LOGGER_MAX_HANDLES]; - LoggerHandle* cur_handle; -} LoggerState; + std::unique_ptr rlog, qlog; +}; kj::Array logger_build_init_data(); std::string logger_get_route_name(); -void logger_init(LoggerState *s, bool has_qlog); -int logger_next(LoggerState *s, const char* root_path, - char* out_segment_path, size_t out_segment_path_len, - int* out_part); -LoggerHandle* logger_get_handle(LoggerState *s); -void logger_close(LoggerState *s, ExitHandler *exit_handler=nullptr); -void logger_log(LoggerState *s, uint8_t* data, size_t data_size, bool in_qlog); - -void lh_log(LoggerHandle* h, uint8_t* data, size_t data_size, bool in_qlog); -void lh_close(LoggerHandle* h); +std::string logger_get_identifier(std::string key); diff --git a/system/loggerd/loggerd.cc b/system/loggerd/loggerd.cc index adb24c913c..3c0ffc1667 100644 --- a/system/loggerd/loggerd.cc +++ b/system/loggerd/loggerd.cc @@ -6,6 +6,7 @@ #include #include +#include "common/params.h" #include "system/loggerd/encoder/encoder.h" #include "system/loggerd/loggerd.h" #include "system/loggerd/video_writer.h" @@ -13,9 +14,7 @@ ExitHandler do_exit; struct LoggerdState { - LoggerState logger = {}; - char segment_path[4096]; - std::atomic rotate_segment; + LoggerState logger; std::atomic last_camera_seen_tms; std::atomic ready_to_rotate; // count of encoders ready to rotate int max_waiting = 0; @@ -23,13 +22,11 @@ struct LoggerdState { }; void logger_rotate(LoggerdState *s) { - int segment = -1; - int err = logger_next(&s->logger, Path::log_root().c_str(), s->segment_path, sizeof(s->segment_path), &segment); - assert(err == 0); - s->rotate_segment = segment; + bool ret =s->logger.next(); + assert(ret); s->ready_to_rotate = 0; s->last_rotate_tms = millis_since_boot(); - LOGW((s->logger.part == 0) ? "logging to %s" : "rotated to %s", s->segment_path); + LOGW((s->logger.segment() == 0) ? "logging to %s" : "rotated to %s", s->logger.segmentPath().c_str()); } void rotate_if_needed(LoggerdState *s) { @@ -85,16 +82,16 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct } int offset_segment_num = idx.getSegmentNum() - re.encoderd_segment_offset; - if (offset_segment_num == s->rotate_segment) { + if (offset_segment_num == s->logger.segment()) { // loggerd is now on the segment that matches this packet // if this is a new segment, we close any possible old segments, move to the new, and process any queued packets - if (re.current_segment != s->rotate_segment) { + if (re.current_segment != s->logger.segment()) { if (re.recording) { re.writer.reset(); re.recording = false; } - re.current_segment = s->rotate_segment; + re.current_segment = s->logger.segment(); re.marked_ready_to_rotate = false; // we are in this segment now, process any queued messages before this one if (!re.q.empty()) { @@ -117,9 +114,9 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct // if we aren't actually recording, don't create the writer if (encoder_info.record) { assert(encoder_info.filename != NULL); - re.writer.reset(new VideoWriter(s->segment_path, + re.writer.reset(new VideoWriter(s->logger.segmentPath().c_str(), encoder_info.filename, idx.getType() != cereal::EncodeIndex::Type::FULL_H_E_V_C, - encoder_info.frame_width, encoder_info.frame_height, encoder_info.fps, idx.getType())); + edata.getWidth(), edata.getHeight(), encoder_info.fps, idx.getType())); // write the header auto header = edata.getHeader(); re.writer->write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); @@ -149,28 +146,28 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct evt.setLogMonoTime(event.getLogMonoTime()); (evt.*(encoder_info.set_encode_idx_func))(idx); auto new_msg = bmsg.toBytes(); - logger_log(&s->logger, (uint8_t *)new_msg.begin(), new_msg.size(), true); // always in qlog? + s->logger.write((uint8_t *)new_msg.begin(), new_msg.size(), true); // always in qlog? bytes_count += new_msg.size(); // free the message, we used it delete msg; - } else if (offset_segment_num > s->rotate_segment) { + } else if (offset_segment_num > s->logger.segment()) { // encoderd packet has a newer segment, this means encoderd has rolled over if (!re.marked_ready_to_rotate) { re.marked_ready_to_rotate = true; ++s->ready_to_rotate; LOGD("rotate %d -> %d ready %d/%d for %s", - s->rotate_segment.load(), offset_segment_num, + s->logger.segment(), offset_segment_num, s->ready_to_rotate.load(), s->max_waiting, name.c_str()); } // queue up all the new segment messages, they go in after the rotate re.q.push_back(msg); } else { - LOGE("%s: encoderd packet has a older segment!!! idx.getSegmentNum():%d s->rotate_segment:%d re.encoderd_segment_offset:%d", - name.c_str(), idx.getSegmentNum(), s->rotate_segment.load(), re.encoderd_segment_offset); + LOGE("%s: encoderd packet has a older segment!!! idx.getSegmentNum():%d s->logger.segment():%d re.encoderd_segment_offset:%d", + name.c_str(), idx.getSegmentNum(), s->logger.segment(), re.encoderd_segment_offset); // free the message, it's useless. this should never happen // actually, this can happen if you restart encoderd - re.encoderd_segment_offset = -s->rotate_segment.load(); + re.encoderd_segment_offset = -s->logger.segment(); delete msg; } @@ -179,19 +176,25 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct void handle_user_flag(LoggerdState *s) { static int prev_segment = -1; - if (s->rotate_segment == prev_segment) return; + if (s->logger.segment() == prev_segment) return; - LOGW("preserving %s", s->segment_path); + LOGW("preserving %s", s->logger.segmentPath().c_str()); #ifdef __APPLE__ - int ret = setxattr(s->segment_path, PRESERVE_ATTR_NAME, &PRESERVE_ATTR_VALUE, 1, 0, 0); + int ret = setxattr(s->logger.segmentPath().c_str(), PRESERVE_ATTR_NAME, &PRESERVE_ATTR_VALUE, 1, 0, 0); #else - int ret = setxattr(s->segment_path, PRESERVE_ATTR_NAME, &PRESERVE_ATTR_VALUE, 1, 0); + int ret = setxattr(s->logger.segmentPath().c_str(), PRESERVE_ATTR_NAME, &PRESERVE_ATTR_VALUE, 1, 0); #endif if (ret) { - LOGE("setxattr %s failed for %s: %s", PRESERVE_ATTR_NAME, s->segment_path, strerror(errno)); + LOGE("setxattr %s failed for %s: %s", PRESERVE_ATTR_NAME, s->logger.segmentPath().c_str(), strerror(errno)); } - prev_segment = s->rotate_segment.load(); + + // mark route for uploading + Params params; + std::string routes = Params().get("AthenadRecentlyViewedRoutes"); + params.put("AthenadRecentlyViewedRoutes", routes + "," + s->logger.routeName()); + + prev_segment = s->logger.segment(); } void loggerd_thread() { @@ -228,9 +231,8 @@ void loggerd_thread() { LoggerdState s; // init logger - logger_init(&s.logger, true); logger_rotate(&s); - Params().put("CurrentRoute", s.logger.route_name); + Params().put("CurrentRoute", s.logger.routeName()); std::map encoder_infos_dict; for (const auto &cam : cameras_logged) { @@ -261,7 +263,7 @@ void loggerd_thread() { s.last_camera_seen_tms = millis_since_boot(); bytes_count += handle_encoder_msg(&s, msg, service.name, remote_encoders[sock], encoder_infos_dict[service.name]); } else { - logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog); + s.logger.write((uint8_t *)msg->getData(), msg->getSize(), in_qlog); bytes_count += msg->getSize(); delete msg; } @@ -283,7 +285,7 @@ void loggerd_thread() { } LOGW("closing logger"); - logger_close(&s.logger, &do_exit); + s.logger.setExitSignal(do_exit.signal); if (do_exit.power_failure) { LOGE("power failure"); diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h index cfc06c28d3..ea288f4861 100644 --- a/system/loggerd/loggerd.h +++ b/system/loggerd/loggerd.h @@ -35,8 +35,8 @@ public: const char *publish_name; const char *filename = NULL; bool record = true; - int frame_width = 1928; - int frame_height = 1208; + int frame_width = -1; + int frame_height = -1; int fps = MAIN_FPS; int bitrate = MAIN_BITRATE; cereal::EncodeIndex::Type encode_type = Hardware::PC() ? cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS diff --git a/system/loggerd/uploader.py b/system/loggerd/uploader.py index 12c6ecdca9..5c8f25368c 100755 --- a/system/loggerd/uploader.py +++ b/system/loggerd/uploader.py @@ -8,24 +8,23 @@ import requests import threading import time import traceback -from pathlib import Path -from typing import BinaryIO, Iterator, List, Optional, Tuple, Union +import datetime +from typing import BinaryIO, Iterator, List, Optional, Tuple from cereal import log import cereal.messaging as messaging from openpilot.common.api import Api from openpilot.common.params import Params from openpilot.common.realtime import set_core_affinity -from openpilot.system.hardware import TICI from openpilot.system.hardware.hw import Paths from openpilot.system.loggerd.xattr_cache import getxattr, setxattr -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog NetworkType = log.DeviceState.NetworkType UPLOAD_ATTR_NAME = 'user.upload' UPLOAD_ATTR_VALUE = b'1' -UPLOAD_QLOG_QCAM_MAX_SIZE = 100 * 1e6 # MB +UPLOAD_QLOG_QCAM_MAX_SIZE = 5 * 1e6 # MB allow_sleep = bool(os.getenv("UPLOADER_SLEEP", "1")) force_wifi = os.getenv("FORCEWIFI") is not None @@ -43,23 +42,24 @@ class FakeResponse: self.request = FakeRequest() -UploadResponse = Union[requests.Response, FakeResponse] - def get_directory_sort(d: str) -> List[str]: return [s.rjust(10, '0') for s in d.rsplit('--', 1)] def listdir_by_creation(d: str) -> List[str]: + if not os.path.isdir(d): + return [] + try: - paths = os.listdir(d) + paths = [f for f in os.listdir(d) if os.path.isdir(os.path.join(d, f))] paths = sorted(paths, key=get_directory_sort) return paths except OSError: cloudlog.exception("listdir_by_creation failed") - return list() + return [] def clear_locks(root: str) -> None: - for logname in os.listdir(root): - path = os.path.join(root, logname) + for logdir in os.listdir(root): + path = os.path.join(root, logdir) try: for fname in os.listdir(path): if fname.endswith(".lock"): @@ -74,34 +74,20 @@ class Uploader: self.api = Api(dongle_id) self.root = root - self.last_resp: Optional[UploadResponse] = None - self.last_exc: Optional[Tuple[Exception, str]] = None - - self.immediate_size = 0 - self.immediate_count = 0 + self.params = Params() # stats for last successfully uploaded file - self.last_time = 0.0 - self.last_speed = 0.0 self.last_filename = "" self.immediate_folders = ["crash/", "boot/"] self.immediate_priority = {"qlog": 0, "qlog.bz2": 0, "qcamera.ts": 1} - def get_upload_sort(self, name: str) -> int: - if name in self.immediate_priority: - return self.immediate_priority[name] - return 1000 + def list_upload_files(self, metered: bool) -> Iterator[Tuple[str, str, str]]: + r = self.params.get("AthenadRecentlyViewedRoutes", encoding="utf8") + requested_routes = [] if r is None else r.split(",") - def list_upload_files(self) -> Iterator[Tuple[str, str, str]]: - if not os.path.isdir(self.root): - return - - self.immediate_size = 0 - self.immediate_count = 0 - - for logname in listdir_by_creation(self.root): - path = os.path.join(self.root, logname) + for logdir in listdir_by_creation(self.root): + path = os.path.join(self.root, logdir) try: names = os.listdir(path) except OSError: @@ -110,29 +96,33 @@ class Uploader: if any(name.endswith(".lock") for name in names): continue - for name in sorted(names, key=self.get_upload_sort): - key = os.path.join(logname, name) + for name in sorted(names, key=lambda n: self.immediate_priority.get(n, 1000)): + key = os.path.join(logdir, name) fn = os.path.join(path, name) # skip files already uploaded try: + ctime = os.path.getctime(fn) is_uploaded = getxattr(fn, UPLOAD_ATTR_NAME) == UPLOAD_ATTR_VALUE except OSError: - cloudlog.event("uploader_getxattr_failed", exc=self.last_exc, key=key, fn=fn) - is_uploaded = True # deleter could have deleted + cloudlog.event("uploader_getxattr_failed", key=key, fn=fn) + # deleter could have deleted, so skip + continue if is_uploaded: continue - try: - if name in self.immediate_priority: - self.immediate_count += 1 - self.immediate_size += os.path.getsize(fn) - except OSError: - pass + # limit uploading on metered connections + if metered: + dt = datetime.timedelta(hours=12) + if logdir in self.immediate_folders and (datetime.datetime.now() - datetime.datetime.fromtimestamp(ctime)) < dt: + continue + + if name == "qcamera.ts" and not any(logdir.startswith(r.split('|')[-1]) for r in requested_routes): + continue yield name, key, fn - def next_file_to_upload(self) -> Optional[Tuple[str, str, str]]: - upload_files = list(self.list_upload_files()) + def next_file_to_upload(self, metered: bool) -> Optional[Tuple[str, str, str]]: + upload_files = list(self.list_upload_files(metered)) for name, key, fn in upload_files: if any(f in fn for f in self.immediate_folders): @@ -144,45 +134,28 @@ class Uploader: return None - def do_upload(self, key: str, fn: str) -> None: - try: - url_resp = self.api.get("v1.4/" + self.dongle_id + "/upload_url/", timeout=10, path=key, access_token=self.api.get_token()) - if url_resp.status_code == 412: - self.last_resp = url_resp - return - - url_resp_json = json.loads(url_resp.text) - url = url_resp_json['url'] - headers = url_resp_json['headers'] - cloudlog.debug("upload_url v1.4 %s %s", url, str(headers)) - - if fake_upload: - cloudlog.debug(f"*** WARNING, THIS IS A FAKE UPLOAD TO {url} ***") - self.last_resp = FakeResponse() - else: - with open(fn, "rb") as f: - data: BinaryIO - if key.endswith('.bz2') and not fn.endswith('.bz2'): - compressed = bz2.compress(f.read()) - data = io.BytesIO(compressed) - else: - data = f - - self.last_resp = requests.put(url, data=data, headers=headers, timeout=10) - except Exception as e: - self.last_exc = (e, traceback.format_exc()) - raise - - def normal_upload(self, key: str, fn: str) -> Optional[UploadResponse]: - self.last_resp = None - self.last_exc = None + def do_upload(self, key: str, fn: str): + url_resp = self.api.get("v1.4/" + self.dongle_id + "/upload_url/", timeout=10, path=key, access_token=self.api.get_token()) + if url_resp.status_code == 412: + return url_resp - try: - self.do_upload(key, fn) - except Exception: - pass + url_resp_json = json.loads(url_resp.text) + url = url_resp_json['url'] + headers = url_resp_json['headers'] + cloudlog.debug("upload_url v1.4 %s %s", url, str(headers)) - return self.last_resp + if fake_upload: + return FakeResponse() + + with open(fn, "rb") as f: + data: BinaryIO + if key.endswith('.bz2') and not fn.endswith('.bz2'): + compressed = bz2.compress(f.read()) + data = io.BytesIO(compressed) + else: + data = f + + return requests.put(url, data=data, headers=headers, timeout=10) def upload(self, name: str, key: str, fn: str, network_type: int, metered: bool) -> bool: try: @@ -201,44 +174,57 @@ class Uploader: success = True else: start_time = time.monotonic() - stat = self.normal_upload(key, fn) + + stat = None + last_exc = None + try: + stat = self.do_upload(key, fn) + except Exception as e: + last_exc = (e, traceback.format_exc()) + if stat is not None and stat.status_code in (200, 201, 401, 403, 412): self.last_filename = fn - self.last_time = time.monotonic() - start_time + dt = time.monotonic() - start_time if stat.status_code == 412: - self.last_speed = 0 cloudlog.event("upload_ignored", key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) else: content_length = int(stat.request.headers.get("Content-Length", 0)) - self.last_speed = (content_length / 1e6) / self.last_time + speed = (content_length / 1e6) / dt cloudlog.event("upload_success", key=key, fn=fn, sz=sz, content_length=content_length, - network_type=network_type, metered=metered, speed=self.last_speed) + network_type=network_type, metered=metered, speed=speed) success = True else: success = False - cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) + cloudlog.event("upload_failed", stat=stat, exc=last_exc, key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) if success: # tag file as uploaded try: setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) except OSError: - cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) + cloudlog.event("uploader_setxattr_failed", exc=last_exc, key=key, fn=fn, sz=sz) return success - def get_msg(self): - msg = messaging.new_message("uploaderState") - us = msg.uploaderState - us.immediateQueueSize = int(self.immediate_size / 1e6) - us.immediateQueueCount = self.immediate_count - us.lastTime = self.last_time - us.lastSpeed = self.last_speed - us.lastFilename = self.last_filename - return msg + def step(self, network_type: int, metered: bool) -> Optional[bool]: + d = self.next_file_to_upload(metered) + if d is None: + return None + + name, key, fn = d + + # qlogs and bootlogs need to be compressed before uploading + if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.bz2')): + key += ".bz2" + + return self.upload(name, key, fn, network_type, metered) + + +def main(exit_event: Optional[threading.Event] = None) -> None: + if exit_event is None: + exit_event = threading.Event() -def uploader_fn(exit_event: threading.Event) -> None: try: set_core_affinity([0, 1, 2, 3]) except Exception: @@ -253,11 +239,7 @@ def uploader_fn(exit_event: threading.Event) -> None: cloudlog.info("uploader missing dongle_id") raise Exception("uploader can't start without dongle id") - if TICI and not Path("/data/media").is_mount(): - cloudlog.warning("NVME not mounted") - sm = messaging.SubMaster(['deviceState']) - pm = messaging.PubMaster(['uploaderState']) uploader = Uploader(dongle_id, Paths.log_root()) backoff = 0.1 @@ -270,31 +252,16 @@ def uploader_fn(exit_event: threading.Event) -> None: time.sleep(60 if offroad else 5) continue - d = uploader.next_file_to_upload() - if d is None: # Nothing to upload - if allow_sleep: - time.sleep(60 if offroad else 5) - continue - - name, key, fn = d - - # qlogs and bootlogs need to be compressed before uploading - if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.bz2')): - key += ".bz2" - - success = uploader.upload(name, key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) - if success: + success = uploader.step(sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) + if success is None: + backoff = 60 if offroad else 5 + elif success: backoff = 0.1 - elif allow_sleep: + else: cloudlog.info("upload backoff %r", backoff) - time.sleep(backoff + random.uniform(0, backoff)) backoff = min(backoff*2, 120) - - pm.send("uploaderState", uploader.get_msg()) - - -def main() -> None: - uploader_fn(threading.Event()) + if allow_sleep: + time.sleep(backoff + random.uniform(0, backoff)) if __name__ == "__main__": diff --git a/system/logmessaged.py b/system/logmessaged.py index c53e20e483..46bf79b0b2 100755 --- a/system/logmessaged.py +++ b/system/logmessaged.py @@ -5,7 +5,7 @@ from typing import NoReturn import cereal.messaging as messaging from openpilot.common.logging_extra import SwagLogFileFormatter from openpilot.system.hardware.hw import Paths -from openpilot.system.swaglog import get_file_handler +from openpilot.common.swaglog import get_file_handler def main() -> NoReturn: @@ -35,13 +35,11 @@ def main() -> NoReturn: continue # then we publish them - msg = messaging.new_message() - msg.logMessage = record + msg = messaging.new_message(None, valid=True, logMessage=record) log_message_sock.send(msg.to_bytes()) if level >= 40: # logging.ERROR - msg = messaging.new_message() - msg.errorLogMessage = record + msg = messaging.new_message(None, valid=True, errorLogMessage=record) error_log_message_sock.send(msg.to_bytes()) finally: sock.close() diff --git a/system/micd.py b/system/micd.py index 72f3b8b490..8b738ebe93 100755 --- a/system/micd.py +++ b/system/micd.py @@ -2,15 +2,15 @@ import numpy as np from cereal import messaging -from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.realtime import Ratekeeper -from openpilot.system.swaglog import cloudlog +from openpilot.common.retry import retry +from openpilot.common.swaglog import cloudlog RATE = 10 FFT_SAMPLES = 4096 REFERENCE_SPL = 2e-5 # newtons/m^2 SAMPLE_RATE = 44100 -FILTER_DT = 1. / (SAMPLE_RATE / FFT_SAMPLES) +SAMPLE_BUFFER = 4096 # (approx 100ms) def calculate_spl(measurements): @@ -50,15 +50,12 @@ class Mic: self.sound_pressure_weighted = 0 self.sound_pressure_level_weighted = 0 - self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False) - def update(self): - msg = messaging.new_message('microphone') + msg = messaging.new_message('microphone', valid=True) msg.microphone.soundPressure = float(self.sound_pressure) msg.microphone.soundPressureWeighted = float(self.sound_pressure_weighted) msg.microphone.soundPressureWeightedDb = float(self.sound_pressure_level_weighted) - msg.microphone.filteredSoundPressureWeightedDb = float(self.spl_filter_weighted.x) self.pm.send('microphone', msg) self.rk.keep_time() @@ -79,16 +76,22 @@ class Mic: self.sound_pressure, _ = calculate_spl(measurements) measurements_weighted = apply_a_weighting(measurements) self.sound_pressure_weighted, self.sound_pressure_level_weighted = calculate_spl(measurements_weighted) - self.spl_filter_weighted.update(self.sound_pressure_level_weighted) self.measurements = self.measurements[FFT_SAMPLES:] + @retry(attempts=7, delay=3) + def get_stream(self, sd): + # reload sounddevice to reinitialize portaudio + sd._terminate() + sd._initialize() + return sd.InputStream(channels=1, samplerate=SAMPLE_RATE, callback=self.callback, blocksize=SAMPLE_BUFFER) + def micd_thread(self): # sounddevice must be imported after forking processes import sounddevice as sd - with sd.InputStream(channels=1, samplerate=SAMPLE_RATE, callback=self.callback) as stream: - cloudlog.info(f"micd stream started: {stream.samplerate=} {stream.channels=} {stream.dtype=} {stream.device=}") + with self.get_stream(sd) as stream: + cloudlog.info(f"micd stream started: {stream.samplerate=} {stream.channels=} {stream.dtype=} {stream.device=}, {stream.blocksize=}") while True: self.update() diff --git a/system/sensord/rawgps/modemdiag.py b/system/qcomgpsd/modemdiag.py similarity index 100% rename from system/sensord/rawgps/modemdiag.py rename to system/qcomgpsd/modemdiag.py diff --git a/system/sensord/rawgps/nmeaport.py b/system/qcomgpsd/nmeaport.py similarity index 96% rename from system/sensord/rawgps/nmeaport.py rename to system/qcomgpsd/nmeaport.py index 01b9b179b9..231096fc5d 100644 --- a/system/sensord/rawgps/nmeaport.py +++ b/system/qcomgpsd/nmeaport.py @@ -120,11 +120,11 @@ def process_nmea_port_messages(device:str="/dev/ttyUSB1") -> NoReturn: def main() -> NoReturn: from openpilot.common.gpio import gpio_init, gpio_set from openpilot.system.hardware.tici.pins import GPIO - from openpilot.system.sensord.rawgps.rawgpsd import at_cmd + from openpilot.system.qcomgpsd.qcomgpsd import at_cmd try: - check_output(["pidof", "rawgpsd"]) - print("rawgpsd is running, please kill openpilot before running this script! (aborted)") + check_output(["pidof", "qcomgpsd"]) + print("qcomgpsd is running, please kill openpilot before running this script! (aborted)") sys.exit(1) except CalledProcessError as e: if e.returncode != 1: # 1 == no process found (boardd not running) diff --git a/system/sensord/rawgps/rawgpsd.py b/system/qcomgpsd/qcomgpsd.py similarity index 85% rename from system/sensord/rawgps/rawgpsd.py rename to system/qcomgpsd/qcomgpsd.py index 787a9316d3..e2a180df86 100755 --- a/system/sensord/rawgps/rawgpsd.py +++ b/system/qcomgpsd/qcomgpsd.py @@ -5,7 +5,7 @@ import signal import itertools import math import time -import pycurl +import requests import shutil import subprocess import datetime @@ -16,10 +16,11 @@ from struct import unpack_from, calcsize, pack from cereal import log import cereal.messaging as messaging from openpilot.common.gpio import gpio_init, gpio_set +from openpilot.common.retry import retry from openpilot.system.hardware.tici.pins import GPIO -from openpilot.system.swaglog import cloudlog -from openpilot.system.sensord.rawgps.modemdiag import ModemDiag, DIAG_LOG_F, setup_logs, send_recv -from openpilot.system.sensord.rawgps.structs import (dict_unpacker, position_report, relist, +from openpilot.common.swaglog import cloudlog +from openpilot.system.qcomgpsd.modemdiag import ModemDiag, DIAG_LOG_F, setup_logs, send_recv +from openpilot.system.qcomgpsd.structs import (dict_unpacker, position_report, relist, gps_measurement_report, gps_measurement_report_sv, glonass_measurement_report, glonass_measurement_report_sv, oemdre_measurement_report, oemdre_measurement_report_sv, oemdre_svpoly_report, @@ -84,58 +85,31 @@ measurementStatusGlonassFields = { "glonassTimeMarkValid": 17 } +@retry(attempts=10, delay=1.0) +def try_setup_logs(diag, logs): + return setup_logs(diag, logs) -def try_setup_logs(diag, log_types): - for _ in range(10): - try: - setup_logs(diag, log_types) - break - except Exception: - cloudlog.exception("setup logs failed, trying again") - time.sleep(1.0) - else: - raise Exception(f"setup logs failed, {log_types=}") - +@retry(attempts=3, delay=1.0) def at_cmd(cmd: str) -> Optional[str]: - for _ in range(3): - try: - return subprocess.check_output(f"mmcli -m any --timeout 30 --command='{cmd}'", shell=True, encoding='utf8') - except subprocess.CalledProcessError: - cloudlog.exception("rawgps.mmcli_command_failed") - time.sleep(1.0) - raise Exception(f"failed to execute mmcli command {cmd=}") - + return subprocess.check_output(f"mmcli -m any --timeout 30 --command='{cmd}'", shell=True, encoding='utf8') def gps_enabled() -> bool: - try: - p = subprocess.check_output("mmcli -m any --command=\"AT+QGPS?\"", shell=True) - return b"QGPS: 1" in p - except subprocess.CalledProcessError as exc: - raise Exception("failed to execute QGPS mmcli command") from exc + return "QGPS: 1" in at_cmd("AT+QGPS?") def download_assistance(): try: - c = pycurl.Curl() - c.setopt(pycurl.URL, ASSISTANCE_URL) - c.setopt(pycurl.NOBODY, 1) - c.setopt(pycurl.CONNECTTIMEOUT, 2) - c.perform() - bytes_n = c.getinfo(pycurl.CONTENT_LENGTH_DOWNLOAD) - c.close() - if bytes_n > 1e5: - cloudlog.error("Qcom assistance data larger than expected") - return + response = requests.get(ASSISTANCE_URL, timeout=5, stream=True) with open(ASSIST_DATA_FILE_DOWNLOAD, 'wb') as fp: - c = pycurl.Curl() - c.setopt(pycurl.URL, ASSISTANCE_URL) - c.setopt(pycurl.CONNECTTIMEOUT, 5) - - c.setopt(pycurl.WRITEDATA, fp) - c.perform() - c.close() - os.rename(ASSIST_DATA_FILE_DOWNLOAD, ASSIST_DATA_FILE) - except pycurl.error: + for chunk in response.iter_content(chunk_size=8192): + fp.write(chunk) + if fp.tell() > 1e5: + cloudlog.error("Qcom assistance data larger than expected") + return + + os.rename(ASSIST_DATA_FILE_DOWNLOAD, ASSIST_DATA_FILE) + + except requests.exceptions.RequestException: cloudlog.exception("Failed to download assistance file") return @@ -154,24 +128,13 @@ def downloader_loop(event): except KeyboardInterrupt: pass +@retry(attempts=5, delay=0.2, ignore_failure=True) def inject_assistance(): - for _ in range(5): - try: - cmd = f"mmcli -m any --timeout 30 --location-inject-assistance-data={ASSIST_DATA_FILE}" - subprocess.check_output(cmd, stderr=subprocess.PIPE, shell=True) - cloudlog.info("successfully loaded assistance data") - return - except subprocess.CalledProcessError as e: - cloudlog.event( - "rawgps.assistance_loading_failed", - error=True, - cmd=e.cmd, - output=e.output, - returncode=e.returncode - ) - time.sleep(0.2) - cloudlog.error("failed to load assistance after retry") + cmd = f"mmcli -m any --timeout 30 --location-inject-assistance-data={ASSIST_DATA_FILE}" + subprocess.check_output(cmd, stderr=subprocess.PIPE, shell=True) + cloudlog.info("successfully loaded assistance data") +@retry(attempts=5, delay=1.0) def setup_quectel(diag: ModemDiag) -> bool: ret = False @@ -321,7 +284,7 @@ def main() -> NoReturn: print("%.4f: got log: %x len %d" % (time.time(), log_type, len(log_payload))) if log_type == LOG_GNSS_OEMDRE_MEASUREMENT_REPORT: - msg = messaging.new_message('qcomGnss') + msg = messaging.new_message('qcomGnss', valid=True) gnss = msg.qcomGnss gnss.logTs = log_time @@ -370,7 +333,7 @@ def main() -> NoReturn: vNED = [report["q_FltVelEnuMps[1]"], report["q_FltVelEnuMps[0]"], -report["q_FltVelEnuMps[2]"]] vNEDsigma = [report["q_FltVelSigmaMps[1]"], report["q_FltVelSigmaMps[0]"], -report["q_FltVelSigmaMps[2]"]] - msg = messaging.new_message('gpsLocation') + msg = messaging.new_message('gpsLocation', valid=True) gps = msg.gpsLocation gps.latitude = report["t_DblFinalPosLatLon[0]"] * 180/math.pi gps.longitude = report["t_DblFinalPosLatLon[1]"] * 180/math.pi @@ -379,7 +342,7 @@ def main() -> NoReturn: gps.bearingDeg = report["q_FltHeadingRad"] * 180/math.pi # TODO needs update if there is another leap second, after june 2024? - dt_timestamp = (datetime.datetime(1980, 1, 6, 0, 0, 0, 0, None) + + dt_timestamp = (datetime.datetime(1980, 1, 6, 0, 0, 0, 0, datetime.timezone.utc) + datetime.timedelta(weeks=report['w_GpsWeekNumber']) + datetime.timedelta(seconds=(1e-3*report['q_GpsFixTimeMs'] - 18))) gps.unixTimestampMillis = dt_timestamp.timestamp()*1e3 @@ -396,7 +359,7 @@ def main() -> NoReturn: pm.send('gpsLocation', msg) elif log_type == LOG_GNSS_OEMDRE_SVPOLY_REPORT: - msg = messaging.new_message('qcomGnss') + msg = messaging.new_message('qcomGnss', valid=True) dat = unpack_svpoly(log_payload) dat = relist(dat) gnss = msg.qcomGnss @@ -433,7 +396,7 @@ def main() -> NoReturn: pm.send('qcomGnss', msg) elif log_type in [LOG_GNSS_GPS_MEASUREMENT_REPORT, LOG_GNSS_GLONASS_MEASUREMENT_REPORT]: - msg = messaging.new_message('qcomGnss') + msg = messaging.new_message('qcomGnss', valid=True) gnss = msg.qcomGnss gnss.logTs = log_time diff --git a/system/sensord/rawgps/structs.py b/system/qcomgpsd/structs.py similarity index 100% rename from system/sensord/rawgps/structs.py rename to system/qcomgpsd/structs.py diff --git a/system/sensord/rawgps/test_rawgps.py b/system/qcomgpsd/tests/test_qcomgpsd.py similarity index 77% rename from system/sensord/rawgps/test_rawgps.py rename to system/qcomgpsd/tests/test_qcomgpsd.py index 3642438132..6c93f7dd93 100755 --- a/system/sensord/rawgps/test_rawgps.py +++ b/system/qcomgpsd/tests/test_qcomgpsd.py @@ -8,7 +8,7 @@ import unittest import subprocess import cereal.messaging as messaging -from openpilot.system.sensord.rawgps.rawgpsd import at_cmd, wait_for_modem +from openpilot.system.qcomgpsd.qcomgpsd import at_cmd, wait_for_modem from openpilot.selfdrive.manager.process_config import managed_processes GOOD_SIGNAL = bool(int(os.getenv("GOOD_SIGNAL", '0'))) @@ -24,7 +24,7 @@ class TestRawgpsd(unittest.TestCase): @classmethod def tearDownClass(cls): - managed_processes['rawgpsd'].stop() + managed_processes['qcomgpsd'].stop() os.system("sudo systemctl restart systemd-resolved") os.system("sudo systemctl restart ModemManager lte") @@ -33,7 +33,7 @@ class TestRawgpsd(unittest.TestCase): self.sm = messaging.SubMaster(['qcomGnss', 'gpsLocation', 'gnssMeasurements']) def tearDown(self): - managed_processes['rawgpsd'].stop() + managed_processes['qcomgpsd'].stop() os.system("sudo systemctl restart systemd-resolved") def _wait_for_output(self, t): @@ -51,7 +51,7 @@ class TestRawgpsd(unittest.TestCase): def test_wait_for_modem(self): os.system("sudo systemctl stop ModemManager") - managed_processes['rawgpsd'].start() + managed_processes['qcomgpsd'].start() assert not self._wait_for_output(5) os.system("sudo systemctl restart ModemManager") @@ -62,19 +62,20 @@ class TestRawgpsd(unittest.TestCase): if not internet: os.system("sudo systemctl stop systemd-resolved") with self.subTest(internet=internet): - managed_processes['rawgpsd'].start() + managed_processes['qcomgpsd'].start() assert self._wait_for_output(7) - managed_processes['rawgpsd'].stop() + managed_processes['qcomgpsd'].stop() def test_turns_off_gnss(self): for s in (0.1, 1, 5): - managed_processes['rawgpsd'].start() - time.sleep(s) - managed_processes['rawgpsd'].stop() + with self.subTest(runtime=s): + managed_processes['qcomgpsd'].start() + time.sleep(s) + managed_processes['qcomgpsd'].stop() - ls = subprocess.check_output("mmcli -m any --location-status --output-json", shell=True, encoding='utf-8') - loc_status = json.loads(ls) - assert set(loc_status['modem']['location']['enabled']) <= {'3gpp-lac-ci'} + ls = subprocess.check_output("mmcli -m any --location-status --output-json", shell=True, encoding='utf-8') + loc_status = json.loads(ls) + assert set(loc_status['modem']['location']['enabled']) <= {'3gpp-lac-ci'} def check_assistance(self, should_be_loaded): @@ -94,29 +95,29 @@ class TestRawgpsd(unittest.TestCase): assert valid_duration == '0' def test_assistance_loading(self): - managed_processes['rawgpsd'].start() + managed_processes['qcomgpsd'].start() assert self._wait_for_output(10) - managed_processes['rawgpsd'].stop() + managed_processes['qcomgpsd'].stop() self.check_assistance(True) def test_no_assistance_loading(self): os.system("sudo systemctl stop systemd-resolved") - managed_processes['rawgpsd'].start() + managed_processes['qcomgpsd'].start() assert self._wait_for_output(10) - managed_processes['rawgpsd'].stop() + managed_processes['qcomgpsd'].stop() self.check_assistance(False) def test_late_assistance_loading(self): os.system("sudo systemctl stop systemd-resolved") - managed_processes['rawgpsd'].start() + managed_processes['qcomgpsd'].start() self._wait_for_output(17) assert self.sm.updated['qcomGnss'] os.system("sudo systemctl restart systemd-resolved") time.sleep(15) - managed_processes['rawgpsd'].stop() + managed_processes['qcomgpsd'].stop() self.check_assistance(True) if __name__ == "__main__": diff --git a/system/sensord/pigeond.py b/system/sensord/pigeond.py index 2e8f151d17..78b3b07498 100755 --- a/system/sensord/pigeond.py +++ b/system/sensord/pigeond.py @@ -11,7 +11,7 @@ from typing import List, Optional, Tuple from cereal import messaging from openpilot.common.params import Params -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog from openpilot.system.hardware import TICI from openpilot.common.gpio import gpio_init, gpio_set from openpilot.system.hardware.tici.pins import GPIO @@ -291,7 +291,7 @@ def run_receiving(pigeon: TTYPigeon, pm: messaging.PubMaster, duration: int = 0) continue # send out to socket - msg = messaging.new_message('ubloxRaw', len(dat)) + msg = messaging.new_message('ubloxRaw', len(dat), valid=True) msg.ubloxRaw = dat[:] pm.send('ubloxRaw', msg) else: diff --git a/system/sensord/sensors_qcom2.cc b/system/sensord/sensors_qcom2.cc index 36d9b4a13e..9cbc24864d 100644 --- a/system/sensord/sensors_qcom2.cc +++ b/system/sensord/sensors_qcom2.cc @@ -134,7 +134,13 @@ int sensor_loop(I2CBus *i2c_bus_imu) { // increase interrupt quality by pinning interrupt and process to core 1 setpriority(PRIO_PROCESS, 0, -18); util::set_core_affinity({1}); - std::system("sudo su -c 'echo 1 > /proc/irq/336/smp_affinity_list'"); + + // TODO: get the IRQ number from gpiochip + std::string irq_path = "/proc/irq/336/smp_affinity_list"; + if (!util::file_exists(irq_path)) { + irq_path = "/proc/irq/335/smp_affinity_list"; + } + std::system(util::string_format("sudo su -c 'echo 1 > %s'", irq_path.c_str()).c_str()); // thread for reading events via interrupts threads.emplace_back(&interrupt_loop, std::ref(sensors_init)); diff --git a/system/timed.py b/system/timed.py new file mode 100755 index 0000000000..39acb2ba12 --- /dev/null +++ b/system/timed.py @@ -0,0 +1,99 @@ +#!/usr/bin/env python3 +import datetime +import os +import subprocess +import time +from typing import NoReturn + +from timezonefinder import TimezoneFinder + +import cereal.messaging as messaging +from openpilot.common.params import Params +from openpilot.common.swaglog import cloudlog +from openpilot.system.hardware import AGNOS + + +def set_timezone(timezone): + valid_timezones = subprocess.check_output('timedatectl list-timezones', shell=True, encoding='utf8').strip().split('\n') + if timezone not in valid_timezones: + cloudlog.error(f"Timezone not supported {timezone}") + return + + cloudlog.debug(f"Setting timezone to {timezone}") + try: + if AGNOS: + tzpath = os.path.join("/usr/share/zoneinfo/", timezone) + subprocess.check_call(f'sudo su -c "ln -snf {tzpath} /data/etc/tmptime && \ + mv /data/etc/tmptime /data/etc/localtime"', shell=True) + subprocess.check_call(f'sudo su -c "echo \"{timezone}\" > /data/etc/timezone"', shell=True) + else: + subprocess.check_call(f'sudo timedatectl set-timezone {timezone}', shell=True) + except subprocess.CalledProcessError: + cloudlog.exception(f"Error setting timezone to {timezone}") + + +def set_time(new_time): + diff = datetime.datetime.now() - new_time + if diff < datetime.timedelta(seconds=10): + cloudlog.debug(f"Time diff too small: {diff}") + return + + cloudlog.debug(f"Setting time to {new_time}") + try: + subprocess.run(f"TZ=UTC date -s '{new_time}'", shell=True, check=True) + except subprocess.CalledProcessError: + cloudlog.exception("timed.failed_setting_time") + + +def main() -> NoReturn: + """ + timed has two responsibilities: + - getting the current time + - getting the current timezone + + GPS directly gives time, and timezone is looked up from GPS position. + AGNOS will also use NTP to update the time. + """ + + params = Params() + tf = TimezoneFinder() + + # Restore timezone from param + tz = params.get("Timezone", encoding='utf8') + tf = TimezoneFinder() + if tz is not None: + cloudlog.debug("Restoring timezone from param") + set_timezone(tz) + + pm = messaging.PubMaster(['clocks']) + sm = messaging.SubMaster(['liveLocationKalman']) + while True: + sm.update(1000) + + msg = messaging.new_message('clocks', valid=True) + msg.clocks.wallTimeNanos = time.time_ns() + pm.send('clocks', msg) + + llk = sm['liveLocationKalman'] + if not llk.gpsOK or (time.monotonic() - sm.logMonoTime['liveLocationKalman']/1e9) > 0.2: + continue + + # set time + # TODO: account for unixTimesatmpMillis being a (usually short) time in the past + gps_time = datetime.datetime.fromtimestamp(llk.unixTimestampMillis / 1000.) + set_time(gps_time) + + # set timezone + pos = llk.positionGeodetic.value + if len(pos) == 3: + gps_timezone = tf.timezone_at(lat=pos[0], lng=pos[1]) + if gps_timezone is None: + cloudlog.critical(f"No timezone found based on {pos=}") + else: + set_timezone(gps_timezone) + params.put_nonblocking("Timezone", gps_timezone) + + time.sleep(10) + +if __name__ == "__main__": + main() diff --git a/system/timezoned.py b/system/timezoned.py deleted file mode 100755 index 91424d33b5..0000000000 --- a/system/timezoned.py +++ /dev/null @@ -1,92 +0,0 @@ -#!/usr/bin/env python3 -import json -import os -import time -import subprocess -from typing import NoReturn - -import requests -from timezonefinder import TimezoneFinder - -from openpilot.common.params import Params -from openpilot.system.hardware import AGNOS -from openpilot.system.swaglog import cloudlog -from openpilot.system.version import get_version - -REQUEST_HEADERS = {'User-Agent': "openpilot-" + get_version()} - - -def set_timezone(valid_timezones, timezone): - if timezone not in valid_timezones: - cloudlog.error(f"Timezone not supported {timezone}") - return - - cloudlog.info(f"Setting timezone to {timezone}") - try: - if AGNOS: - tzpath = os.path.join("/usr/share/zoneinfo/", timezone) - subprocess.check_call(f'sudo su -c "ln -snf {tzpath} /data/etc/tmptime && \ - mv /data/etc/tmptime /data/etc/localtime"', shell=True) - subprocess.check_call(f'sudo su -c "echo \"{timezone}\" > /data/etc/timezone"', shell=True) - else: - subprocess.check_call(f'sudo timedatectl set-timezone {timezone}', shell=True) - except subprocess.CalledProcessError: - cloudlog.exception(f"Error setting timezone to {timezone}") - - -def main() -> NoReturn: - params = Params() - tf = TimezoneFinder() - - # Get allowed timezones - valid_timezones = subprocess.check_output('timedatectl list-timezones', shell=True, encoding='utf8').strip().split('\n') - - while True: - time.sleep(60) - - is_onroad = not params.get_bool("IsOffroad") - if is_onroad: - continue - - # Set based on param - timezone = params.get("Timezone", encoding='utf8') - if timezone is not None: - cloudlog.debug("Setting timezone based on param") - set_timezone(valid_timezones, timezone) - continue - - location = params.get("LastGPSPosition", encoding='utf8') - - # Find timezone based on IP geolocation if no gps location is available - if location is None: - cloudlog.debug("Setting timezone based on IP lookup") - try: - r = requests.get("https://ipapi.co/timezone", headers=REQUEST_HEADERS, timeout=10) - if r.status_code == 200: - set_timezone(valid_timezones, r.text) - else: - cloudlog.error(f"Unexpected status code from api {r.status_code}") - - time.sleep(3600) # Don't make too many API requests - except requests.exceptions.RequestException: - cloudlog.exception("Error getting timezone based on IP") - continue - - # Find timezone by reverse geocoding the last known gps location - else: - cloudlog.debug("Setting timezone based on GPS location") - try: - location = json.loads(location) - except Exception: - cloudlog.exception("Error parsing location") - continue - - timezone = tf.timezone_at(lng=location['longitude'], lat=location['latitude']) - if timezone is None: - cloudlog.error(f"No timezone found based on location, {location}") - continue - set_timezone(valid_timezones, timezone) - - -if __name__ == "__main__": - main() diff --git a/system/version.py b/system/version.py index 82e99fd416..e34458f16f 100755 --- a/system/version.py +++ b/system/version.py @@ -1,20 +1,20 @@ #!/usr/bin/env python3 import os import subprocess -from typing import List, Optional +from typing import List, Callable, TypeVar from functools import lru_cache from openpilot.common.basedir import BASEDIR -from openpilot.system.swaglog import cloudlog +from openpilot.common.swaglog import cloudlog -RELEASE_BRANCHES = ['release3-staging', 'dashcam3-staging', 'release3', 'dashcam3', 'nightly'] +RELEASE_BRANCHES = ['release3-staging', 'release3', 'nightly'] TESTED_BRANCHES = RELEASE_BRANCHES + ['devel', 'devel-staging'] training_version: bytes = b"0.2.0" terms_version: bytes = b"2" - -def cache(user_function, /): +_RT = TypeVar("_RT") +def cache(user_function: Callable[..., _RT], /) -> Callable[..., _RT]: return lru_cache(maxsize=None)(user_function) @@ -22,7 +22,7 @@ def run_cmd(cmd: List[str]) -> str: return subprocess.check_output(cmd, encoding='utf8').strip() -def run_cmd_default(cmd: List[str], default: Optional[str] = None) -> Optional[str]: +def run_cmd_default(cmd: List[str], default: str = "") -> str: try: return run_cmd(cmd) except subprocess.CalledProcessError: @@ -30,41 +30,42 @@ def run_cmd_default(cmd: List[str], default: Optional[str] = None) -> Optional[s @cache -def get_commit(branch: str = "HEAD", default: Optional[str] = None) -> Optional[str]: - return run_cmd_default(["git", "rev-parse", branch], default=default) +def get_commit(branch: str = "HEAD") -> str: + return run_cmd_default(["git", "rev-parse", branch]) @cache -def get_short_branch(default: Optional[str] = None) -> Optional[str]: - return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "HEAD"], default=default) +def get_commit_date(commit: str = "HEAD") -> str: + return run_cmd_default(["git", "show", "--no-patch", "--format='%ct %ci'", commit]) @cache -def get_branch(default: Optional[str] = None) -> Optional[str]: - return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"], default=default) +def get_short_branch() -> str: + return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "HEAD"]) @cache -def get_origin(default: Optional[str] = None) -> Optional[str]: +def get_branch() -> str: + return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"]) + + +@cache +def get_origin() -> str: try: local_branch = run_cmd(["git", "name-rev", "--name-only", "HEAD"]) tracking_remote = run_cmd(["git", "config", "branch." + local_branch + ".remote"]) return run_cmd(["git", "config", "remote." + tracking_remote + ".url"]) except subprocess.CalledProcessError: # Not on a branch, fallback - return run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) + return run_cmd_default(["git", "config", "--get", "remote.origin.url"]) @cache -def get_normalized_origin(default: Optional[str] = None) -> Optional[str]: - origin: Optional[str] = get_origin() - - if origin is None: - return default - - return origin.replace("git@", "", 1) \ - .replace(".git", "", 1) \ - .replace("https://", "", 1) \ - .replace(":", "/", 1) +def get_normalized_origin() -> str: + return get_origin() \ + .replace("git@", "", 1) \ + .replace(".git", "", 1) \ + .replace("https://", "", 1) \ + .replace(":", "/", 1) @cache @@ -75,7 +76,7 @@ def get_version() -> str: @cache def get_short_version() -> str: - return get_version().split('-')[0] # type: ignore + return get_version().split('-')[0] @cache def is_prebuilt() -> bool: @@ -86,12 +87,7 @@ def is_prebuilt() -> bool: def is_comma_remote() -> bool: # note to fork maintainers, this is used for release metrics. please do not # touch this to get rid of the orange startup alert. there's better ways to do that - origin: Optional[str] = get_origin() - if origin is None: - return False - - return origin.startswith(('git@github.com:commaai', 'https://github.com/commaai')) - + return get_normalized_origin() == "github.com/commaai/openpilot" @cache def is_tested_branch() -> bool: @@ -105,7 +101,7 @@ def is_release_branch() -> bool: def is_dirty() -> bool: origin = get_origin() branch = get_branch() - if (origin is None) or (branch is None): + if not origin or not branch: return True dirty = False @@ -141,3 +137,4 @@ if __name__ == "__main__": print(f"Branch: {get_branch()}") print(f"Short branch: {get_short_branch()}") print(f"Prebuilt: {is_prebuilt()}") + print(f"Commit date: {get_commit_date()}") diff --git a/common/kalman/__init__.py b/system/webrtc/__init__.py similarity index 100% rename from common/kalman/__init__.py rename to system/webrtc/__init__.py diff --git a/system/webrtc/device/audio.py b/system/webrtc/device/audio.py new file mode 100644 index 0000000000..3c78be6752 --- /dev/null +++ b/system/webrtc/device/audio.py @@ -0,0 +1,110 @@ +import asyncio +import io +from typing import Optional, List, Tuple + +import aiortc +import av +import numpy as np +import pyaudio + + +class AudioInputStreamTrack(aiortc.mediastreams.AudioStreamTrack): + PYAUDIO_TO_AV_FORMAT_MAP = { + pyaudio.paUInt8: 'u8', + pyaudio.paInt16: 's16', + pyaudio.paInt24: 's24', + pyaudio.paInt32: 's32', + pyaudio.paFloat32: 'flt', + } + + def __init__(self, audio_format: int = pyaudio.paInt16, rate: int = 16000, channels: int = 1, packet_time: float = 0.020, device_index: Optional[int] = None): + super().__init__() + + self.p = pyaudio.PyAudio() + chunk_size = int(packet_time * rate) + self.stream = self.p.open(format=audio_format, + channels=channels, + rate=rate, + frames_per_buffer=chunk_size, + input=True, + input_device_index=device_index) + self.format = audio_format + self.rate = rate + self.channels = channels + self.packet_time = packet_time + self.chunk_size = chunk_size + self.pts = 0 + + async def recv(self): + mic_data = self.stream.read(self.chunk_size) + mic_array = np.frombuffer(mic_data, dtype=np.int16) + mic_array = np.expand_dims(mic_array, axis=0) + layout = 'stereo' if self.channels > 1 else 'mono' + frame = av.AudioFrame.from_ndarray(mic_array, format=self.PYAUDIO_TO_AV_FORMAT_MAP[self.format], layout=layout) + frame.rate = self.rate + frame.pts = self.pts + self.pts += frame.samples + + return frame + + +class AudioOutputSpeaker: + def __init__(self, audio_format: int = pyaudio.paInt16, rate: int = 48000, channels: int = 2, packet_time: float = 0.2, device_index: Optional[int] = None): + + chunk_size = int(packet_time * rate) + self.p = pyaudio.PyAudio() + self.buffer = io.BytesIO() + self.channels = channels + self.stream = self.p.open(format=audio_format, + channels=channels, + rate=rate, + frames_per_buffer=chunk_size, + output=True, + output_device_index=device_index, + stream_callback=self.__pyaudio_callback) + self.tracks_and_tasks: List[Tuple[aiortc.MediaStreamTrack, Optional[asyncio.Task]]] = [] + + def __pyaudio_callback(self, in_data, frame_count, time_info, status): + if self.buffer.getbuffer().nbytes < frame_count * self.channels * 2: + buff = b'\x00\x00' * frame_count * self.channels + elif self.buffer.getbuffer().nbytes > 115200: # 3x the usual read size + self.buffer.seek(0) + buff = self.buffer.read(frame_count * self.channels * 4) + buff = buff[:frame_count * self.channels * 2] + self.buffer.seek(2) + else: + self.buffer.seek(0) + buff = self.buffer.read(frame_count * self.channels * 2) + self.buffer.seek(2) + return (buff, pyaudio.paContinue) + + async def __consume(self, track): + while True: + try: + frame = await track.recv() + except aiortc.MediaStreamError: + return + + self.buffer.write(bytes(frame.planes[0])) + + def hasTrack(self, track: aiortc.MediaStreamTrack) -> bool: + return any(t == track for t, _ in self.tracks_and_tasks) + + def addTrack(self, track: aiortc.MediaStreamTrack): + if not self.hasTrack(track): + self.tracks_and_tasks.append((track, None)) + + def start(self): + for index, (track, task) in enumerate(self.tracks_and_tasks): + if task is None: + self.tracks_and_tasks[index] = (track, asyncio.create_task(self.__consume(track))) + + def stop(self): + for _, task in self.tracks_and_tasks: + if task is not None: + task.cancel() + + self.tracks_and_tasks = [] + self.stream.stop_stream() + self.stream.close() + self.p.terminate() diff --git a/system/webrtc/device/video.py b/system/webrtc/device/video.py new file mode 100644 index 0000000000..314f812834 --- /dev/null +++ b/system/webrtc/device/video.py @@ -0,0 +1,44 @@ +import asyncio +from typing import Optional + +import av +from teleoprtc.tracks import TiciVideoStreamTrack + +from cereal import messaging +from openpilot.common.realtime import DT_MDL, DT_DMON + + +class LiveStreamVideoStreamTrack(TiciVideoStreamTrack): + camera_to_sock_mapping = { + "driver": "livestreamDriverEncodeData", + "wideRoad": "livestreamWideRoadEncodeData", + "road": "livestreamRoadEncodeData", + } + + def __init__(self, camera_type: str): + dt = DT_DMON if camera_type == "driver" else DT_MDL + super().__init__(camera_type, dt) + + self._sock = messaging.sub_sock(self.camera_to_sock_mapping[camera_type], conflate=True) + self._pts = 0 + + async def recv(self): + while True: + msg = messaging.recv_one_or_none(self._sock) + if msg is not None: + break + await asyncio.sleep(0.005) + + evta = getattr(msg, msg.which()) + + packet = av.Packet(evta.header + evta.data) + packet.time_base = self._time_base + packet.pts = self._pts + + self.log_debug("track sending frame %s", self._pts) + self._pts += self._dt * self._clock_rate + + return packet + + def codec_preference(self) -> Optional[str]: + return "H264" diff --git a/system/webrtc/schema.py b/system/webrtc/schema.py new file mode 100644 index 0000000000..f659b34293 --- /dev/null +++ b/system/webrtc/schema.py @@ -0,0 +1,43 @@ +import capnp +from typing import Union, List, Dict, Any + + +def generate_type(type_walker, schema_walker) -> Union[str, List[Any], Dict[str, Any]]: + data_type = next(type_walker) + if data_type.which() == 'struct': + return generate_struct(next(schema_walker)) + elif data_type.which() == 'list': + _ = next(schema_walker) + return [generate_type(type_walker, schema_walker)] + elif data_type.which() == 'enum': + return "text" + else: + return str(data_type.which()) + + +def generate_struct(schema: capnp.lib.capnp._StructSchema) -> Dict[str, Any]: + return {field: generate_field(schema.fields[field]) for field in schema.fields if not field.endswith("DEPRECATED")} + + +def generate_field(field: capnp.lib.capnp._StructSchemaField) -> Union[str, List[Any], Dict[str, Any]]: + def schema_walker(field): + yield field.schema + + s = field.schema + while hasattr(s, 'elementType'): + s = s.elementType + yield s + + def type_walker(field): + yield field.proto.slot.type + + t = field.proto.slot.type + while hasattr(getattr(t, t.which()), 'elementType'): + t = getattr(t, t.which()).elementType + yield t + + if field.proto.which() == "slot": + schema_gen, type_gen = schema_walker(field), type_walker(field) + return generate_type(type_gen, schema_gen) + else: + return generate_struct(field.schema) diff --git a/system/webrtc/webrtcd.py b/system/webrtc/webrtcd.py new file mode 100755 index 0000000000..cc26d50daf --- /dev/null +++ b/system/webrtc/webrtcd.py @@ -0,0 +1,253 @@ +#!/usr/bin/env python3 + +import argparse +import asyncio +import json +import uuid +import logging +from dataclasses import dataclass, field +from typing import Any, List, Optional, Union, TYPE_CHECKING + +# aiortc and its dependencies have lots of internal warnings :( +import warnings +warnings.filterwarnings("ignore", category=DeprecationWarning) + +import capnp +from aiohttp import web +if TYPE_CHECKING: + from aiortc.rtcdatachannel import RTCDataChannel + +from openpilot.system.webrtc.schema import generate_field +from cereal import messaging, log + + +class CerealOutgoingMessageProxy: + def __init__(self, sm: messaging.SubMaster): + self.sm = sm + self.channels: List['RTCDataChannel'] = [] + + def add_channel(self, channel: 'RTCDataChannel'): + self.channels.append(channel) + + def to_json(self, msg_content: Any): + if isinstance(msg_content, capnp._DynamicStructReader): + msg_dict = msg_content.to_dict() + elif isinstance(msg_content, capnp._DynamicListReader): + msg_dict = [self.to_json(msg) for msg in msg_content] + elif isinstance(msg_content, bytes): + msg_dict = msg_content.decode() + else: + msg_dict = msg_content + + return msg_dict + + def update(self): + # this is blocking in async context... + self.sm.update(0) + for service, updated in self.sm.updated.items(): + if not updated: + continue + msg_dict = self.to_json(self.sm[service]) + mono_time, valid = self.sm.logMonoTime[service], self.sm.valid[service] + outgoing_msg = {"type": service, "logMonoTime": mono_time, "valid": valid, "data": msg_dict} + encoded_msg = json.dumps(outgoing_msg).encode() + for channel in self.channels: + channel.send(encoded_msg) + + +class CerealIncomingMessageProxy: + def __init__(self, pm: messaging.PubMaster): + self.pm = pm + + def send(self, message: bytes): + msg_json = json.loads(message) + msg_type, msg_data = msg_json["type"], msg_json["data"] + size = None + if not isinstance(msg_data, dict): + size = len(msg_data) + + msg = messaging.new_message(msg_type, size=size) + setattr(msg, msg_type, msg_data) + self.pm.send(msg_type, msg) + + +class CerealProxyRunner: + def __init__(self, proxy: CerealOutgoingMessageProxy): + self.proxy = proxy + self.is_running = False + self.task = None + self.logger = logging.getLogger("webrtcd") + + def start(self): + assert self.task is None + self.task = asyncio.create_task(self.run()) + + def stop(self): + if self.task is None or self.task.done(): + return + self.task.cancel() + self.task = None + + async def run(self): + from aiortc.exceptions import InvalidStateError + + while True: + try: + self.proxy.update() + except InvalidStateError: + self.logger.warning("Cereal outgoing proxy invalid state (connection closed)") + break + except Exception as ex: + self.logger.error("Cereal outgoing proxy failure: %s", ex) + await asyncio.sleep(0.01) + + +class StreamSession: + def __init__(self, sdp: str, cameras: List[str], incoming_services: List[str], outgoing_services: List[str], debug_mode: bool = False): + from aiortc.mediastreams import VideoStreamTrack, AudioStreamTrack + from aiortc.contrib.media import MediaBlackhole + from openpilot.system.webrtc.device.video import LiveStreamVideoStreamTrack + from openpilot.system.webrtc.device.audio import AudioInputStreamTrack, AudioOutputSpeaker + from teleoprtc import WebRTCAnswerBuilder + from teleoprtc.info import parse_info_from_offer + + config = parse_info_from_offer(sdp) + builder = WebRTCAnswerBuilder(sdp) + + assert len(cameras) == config.n_expected_camera_tracks, "Incoming stream has misconfigured number of video tracks" + for cam in cameras: + track = LiveStreamVideoStreamTrack(cam) if not debug_mode else VideoStreamTrack() + builder.add_video_stream(cam, track) + if config.expected_audio_track: + track = AudioInputStreamTrack() if not debug_mode else AudioStreamTrack() + builder.add_audio_stream(track) + if config.incoming_audio_track: + self.audio_output_cls = AudioOutputSpeaker if not debug_mode else MediaBlackhole + builder.offer_to_receive_audio_stream() + + self.stream = builder.stream() + self.identifier = str(uuid.uuid4()) + + self.outgoing_bridge = CerealOutgoingMessageProxy(messaging.SubMaster(outgoing_services)) + self.incoming_bridge = CerealIncomingMessageProxy(messaging.PubMaster(incoming_services)) + self.outgoing_bridge_runner = CerealProxyRunner(self.outgoing_bridge) + + self.audio_output: Optional[Union[AudioOutputSpeaker, MediaBlackhole]] = None + self.run_task: Optional[asyncio.Task] = None + self.logger = logging.getLogger("webrtcd") + self.logger.info("New stream session (%s), cameras %s, audio in %s out %s, incoming services %s, outgoing services %s", + self.identifier, cameras, config.incoming_audio_track, config.expected_audio_track, incoming_services, outgoing_services) + + def start(self): + self.run_task = asyncio.create_task(self.run()) + + def stop(self): + if self.run_task.done(): + return + self.run_task.cancel() + self.run_task = None + asyncio.run(self.post_run_cleanup()) + + async def get_answer(self): + return await self.stream.start() + + async def message_handler(self, message: bytes): + try: + self.incoming_bridge.send(message) + except Exception as ex: + self.logger.error("Cereal incoming proxy failure: %s", ex) + + async def run(self): + try: + await self.stream.wait_for_connection() + if self.stream.has_messaging_channel(): + self.stream.set_message_handler(self.message_handler) + channel = self.stream.get_messaging_channel() + self.outgoing_bridge_runner.proxy.add_channel(channel) + self.outgoing_bridge_runner.start() + if self.stream.has_incoming_audio_track(): + track = self.stream.get_incoming_audio_track(buffered=False) + self.audio_output = self.audio_output_cls() + self.audio_output.addTrack(track) + self.audio_output.start() + self.logger.info("Stream session (%s) connected", self.identifier) + + await self.stream.wait_for_disconnection() + await self.post_run_cleanup() + + self.logger.info("Stream session (%s) ended", self.identifier) + except Exception as ex: + self.logger.error("Stream session failure: %s", ex) + + async def post_run_cleanup(self): + await self.stream.stop() + self.outgoing_bridge_runner.stop() + if self.audio_output: + self.audio_output.stop() + + +@dataclass +class StreamRequestBody: + sdp: str + cameras: List[str] + bridge_services_in: List[str] = field(default_factory=list) + bridge_services_out: List[str] = field(default_factory=list) + + +async def get_stream(request: 'web.Request'): + stream_dict, debug_mode = request.app['streams'], request.app['debug'] + raw_body = await request.json() + body = StreamRequestBody(**raw_body) + + session = StreamSession(body.sdp, body.cameras, body.bridge_services_in, body.bridge_services_out, debug_mode) + answer = await session.get_answer() + session.start() + + stream_dict[session.identifier] = session + + return web.json_response({"sdp": answer.sdp, "type": answer.type}) + + +async def get_schema(request: 'web.Request'): + services = request.query["services"].split(",") + services = [s for s in services if s] + assert all(s in log.Event.schema.fields and not s.endswith("DEPRECATED") for s in services), "Invalid service name" + schema_dict = {s: generate_field(log.Event.schema.fields[s]) for s in services} + return web.json_response(schema_dict) + + +async def on_shutdown(app: 'web.Application'): + for session in app['streams'].values(): + session.stop() + del app['streams'] + + +def webrtcd_thread(host: str, port: int, debug: bool): + logging.basicConfig(level=logging.CRITICAL, handlers=[logging.StreamHandler()]) + logging_level = logging.DEBUG if debug else logging.INFO + logging.getLogger("WebRTCStream").setLevel(logging_level) + logging.getLogger("webrtcd").setLevel(logging_level) + + app = web.Application() + + app['streams'] = dict() + app['debug'] = debug + app.on_shutdown.append(on_shutdown) + app.router.add_post("/stream", get_stream) + app.router.add_get("/schema", get_schema) + + web.run_app(app, host=host, port=port) + + +def main(): + parser = argparse.ArgumentParser(description="WebRTC daemon") + parser.add_argument("--host", type=str, default="0.0.0.0", help="Host to listen on") + parser.add_argument("--port", type=int, default=5001, help="Port to listen on") + parser.add_argument("--debug", action="store_true", help="Enable debug mode") + args = parser.parse_args() + + webrtcd_thread(args.host, args.port, args.debug) + + +if __name__=="__main__": + main() diff --git a/teleoprtc/__init__.py b/teleoprtc/__init__.py new file mode 100644 index 0000000000..4104f949bc --- /dev/null +++ b/teleoprtc/__init__.py @@ -0,0 +1,2 @@ +from teleoprtc.builder import WebRTCOfferBuilder, WebRTCAnswerBuilder # noqa +from teleoprtc.stream import WebRTCBaseStream, StreamingOffer, ConnectionProvider, MessageHandler # noqa \ No newline at end of file diff --git a/teleoprtc/builder.py b/teleoprtc/builder.py new file mode 100644 index 0000000000..9ec183e267 --- /dev/null +++ b/teleoprtc/builder.py @@ -0,0 +1,79 @@ +import abc +from typing import List, Dict + +import aiortc + +from teleoprtc.stream import WebRTCBaseStream, WebRTCOfferStream, WebRTCAnswerStream, ConnectionProvider +from teleoprtc.tracks import TiciVideoStreamTrack, TiciTrackWrapper + + +class WebRTCStreamBuilder(abc.ABC): + @abc.abstractmethod + def stream(self) -> WebRTCBaseStream: + raise NotImplementedError + + +class WebRTCOfferBuilder(WebRTCStreamBuilder): + def __init__(self, connection_provider: ConnectionProvider): + self.connection_provider = connection_provider + self.requested_camera_types: List[str] = [] + self.requested_audio = False + self.audio_tracks: List[aiortc.MediaStreamTrack] = [] + self.messaging_enabled = False + + def offer_to_receive_video_stream(self, camera_type: str): + assert camera_type in ["driver", "wideRoad", "road"] + self.requested_camera_types.append(camera_type) + + def offer_to_receive_audio_stream(self): + self.requested_audio = True + + def add_audio_stream(self, track: aiortc.MediaStreamTrack): + assert len(self.audio_tracks) == 0 + self.audio_tracks = [track] + + def add_messaging(self): + self.messaging_enabled = True + + def stream(self) -> WebRTCBaseStream: + return WebRTCOfferStream( + self.connection_provider, + consumed_camera_types=self.requested_camera_types, + consume_audio=self.requested_audio, + video_producer_tracks=[], + audio_producer_tracks=self.audio_tracks, + should_add_data_channel=self.messaging_enabled, + ) + + +class WebRTCAnswerBuilder(WebRTCStreamBuilder): + def __init__(self, offer_sdp: str): + self.offer_sdp = offer_sdp + self.video_tracks: Dict[str, aiortc.MediaStreamTrack] = dict() + self.requested_audio = False + self.audio_tracks: List[aiortc.MediaStreamTrack] = [] + + def offer_to_receive_audio_stream(self): + self.requested_audio = True + + def add_video_stream(self, camera_type: str, track: aiortc.MediaStreamTrack): + assert camera_type not in self.video_tracks + assert camera_type in ["driver", "wideRoad", "road"] + if not isinstance(track, TiciVideoStreamTrack): + track = TiciTrackWrapper(camera_type, track) + self.video_tracks[camera_type] = track + + def add_audio_stream(self, track: aiortc.MediaStreamTrack): + assert len(self.audio_tracks) == 0 + self.audio_tracks = [track] + + def stream(self) -> WebRTCBaseStream: + description = aiortc.RTCSessionDescription(sdp=self.offer_sdp, type="offer") + return WebRTCAnswerStream( + description, + consumed_camera_types=[], + consume_audio=self.requested_audio, + video_producer_tracks=list(self.video_tracks.values()), + audio_producer_tracks=self.audio_tracks, + should_add_data_channel=False, + ) diff --git a/teleoprtc/info.py b/teleoprtc/info.py new file mode 100644 index 0000000000..b47ec3ff1f --- /dev/null +++ b/teleoprtc/info.py @@ -0,0 +1,27 @@ + +import dataclasses + +import aiortc + + +@dataclasses.dataclass +class StreamingMediaInfo: + n_expected_camera_tracks: int + expected_audio_track: bool + incoming_audio_track: bool + incoming_datachannel: bool + + +def parse_info_from_offer(sdp: str) -> StreamingMediaInfo: + """ + helper function to parse info about outgoing and incoming streams from an offer sdp + """ + desc = aiortc.sdp.SessionDescription.parse(sdp) + audio_tracks = [m for m in desc.media if m.kind == "audio"] + video_tracks = [m for m in desc.media if m.kind == "video" and m.direction in ["recvonly", "sendrecv"]] + application_tracks = [m for m in desc.media if m.kind == "application"] + has_incoming_audio_track = next((t for t in audio_tracks if t.direction in ["sendonly", "sendrecv"]), None) is not None + has_incoming_datachannel = len(application_tracks) > 0 + expects_outgoing_audio_track = next((t for t in audio_tracks if t.direction in ["recvonly", "sendrecv"]), None) is not None + + return StreamingMediaInfo(len(video_tracks), expects_outgoing_audio_track, has_incoming_audio_track, has_incoming_datachannel) diff --git a/teleoprtc/stream.py b/teleoprtc/stream.py new file mode 100644 index 0000000000..a928c14897 --- /dev/null +++ b/teleoprtc/stream.py @@ -0,0 +1,302 @@ +import abc +import asyncio +import dataclasses +import logging +from typing import Callable, Awaitable, Dict, List, Any, Optional + +import aiortc +from aiortc.contrib.media import MediaRelay + +from teleoprtc.tracks import parse_video_track_id + + +@dataclasses.dataclass +class StreamingOffer: + sdp: str + video: List[str] + + +ConnectionProvider = Callable[[StreamingOffer], Awaitable[aiortc.RTCSessionDescription]] +MessageHandler = Callable[[bytes], Awaitable[None]] + + +class WebRTCBaseStream(abc.ABC): + def __init__(self, + consumed_camera_types: List[str], + consume_audio: bool, + video_producer_tracks: List[aiortc.MediaStreamTrack], + audio_producer_tracks: List[aiortc.MediaStreamTrack], + should_add_data_channel: bool): + self.peer_connection = aiortc.RTCPeerConnection() + self.media_relay = MediaRelay() + self.expected_incoming_camera_types = consumed_camera_types + self.expected_incoming_audio = consume_audio + self.expected_number_of_incoming_media: Optional[int] = None + + self.incoming_camera_tracks: Dict[str, aiortc.MediaStreamTrack] = dict() + self.incoming_audio_tracks: List[aiortc.MediaStreamTrack] = [] + self.outgoing_video_tracks: List[aiortc.MediaStreamTrack] = video_producer_tracks + self.outgoing_audio_tracks: List[aiortc.MediaStreamTrack] = audio_producer_tracks + + self.should_add_data_channel = should_add_data_channel + self.messaging_channel: Optional[aiortc.RTCDataChannel] = None + self.incoming_message_handlers: List[MessageHandler] = [] + + self.incoming_media_ready_event = asyncio.Event() + self.messaging_channel_ready_event = asyncio.Event() + self.connection_attempted_event = asyncio.Event() + self.connection_stopped_event = asyncio.Event() + + self.peer_connection.on("connectionstatechange", self._on_connectionstatechange) + self.peer_connection.on("datachannel", self._on_incoming_datachannel) + self.peer_connection.on("track", self._on_incoming_track) + + self.logger = logging.getLogger("WebRTCStream") + + def _log_debug(self, msg: Any, *args): + self.logger.debug(f"{type(self)}() {msg}", *args) + + @property + def _number_of_incoming_media(self) -> int: + media = len(self.incoming_camera_tracks) + len(self.incoming_audio_tracks) + # if stream does not add data_channel, then it means its incoming + media += int(self.messaging_channel is not None) if not self.should_add_data_channel else 0 + return media + + def _add_consumer_transceivers(self): + for _ in self.expected_incoming_camera_types: + self.peer_connection.addTransceiver("video", direction="recvonly") + if self.expected_incoming_audio: + self.peer_connection.addTransceiver("audio", direction="recvonly") + + def _find_trackless_transceiver(self, kind: str) -> Optional[aiortc.RTCRtpTransceiver]: + transceivers = self.peer_connection.getTransceivers() + target_transceiver = None + for t in transceivers: + if t.kind == kind and t.sender.track is None: + target_transceiver = t + break + + return target_transceiver + + def _add_producer_tracks(self): + for track in self.outgoing_video_tracks: + target_transceiver = self._find_trackless_transceiver(track.kind) + if target_transceiver is None: + self.peer_connection.addTransceiver(track.kind, direction="sendonly") + + sender = self.peer_connection.addTrack(track) + if hasattr(track, "codec_preference") and track.codec_preference() is not None: + transceiver = next(t for t in self.peer_connection.getTransceivers() if t.sender == sender) + self._force_codec(transceiver, track.codec_preference(), "video") + for track in self.outgoing_audio_tracks: + target_transceiver = self._find_trackless_transceiver(track.kind) + if target_transceiver is None: + self.peer_connection.addTransceiver(track.kind, direction="sendonly") + + self.peer_connection.addTrack(track) + + def _add_messaging_channel(self, channel: Optional[aiortc.RTCDataChannel] = None): + if not channel: + channel = self.peer_connection.createDataChannel("data", ordered=True) + + for handler in self.incoming_message_handlers: + channel.on("message", handler) + + if channel.readyState == "open": + self.messaging_channel_ready_event.set() + else: + channel.on("open", lambda: self.messaging_channel_ready_event.set()) + self.messaging_channel = channel + + def _force_codec(self, transceiver: aiortc.RTCRtpTransceiver, codec: str, stream_type: str): + codec_mime = f"{stream_type}/{codec.upper()}" + rtp_codecs = aiortc.RTCRtpSender.getCapabilities(stream_type).codecs + rtp_codec = [c for c in rtp_codecs if c.mimeType == codec_mime] + transceiver.setCodecPreferences(rtp_codec) + + def _on_connectionstatechange(self): + self._log_debug("connection state is %s", self.peer_connection.connectionState) + if self.peer_connection.connectionState in ['connected', 'failed']: + self.connection_attempted_event.set() + if self.peer_connection.connectionState in ['disconnected', 'closed', 'failed']: + self.connection_stopped_event.set() + + def _on_incoming_track(self, track: aiortc.MediaStreamTrack): + self._log_debug("got track: %s %s", track.kind, track.id) + if track.kind == "video": + camera_type, _ = parse_video_track_id(track.id) + if camera_type in self.expected_incoming_camera_types: + self.incoming_camera_tracks[camera_type] = track + elif track.kind == "audio": + if self.expected_incoming_audio: + self.incoming_audio_tracks.append(track) + self._on_after_media() + + def _on_incoming_datachannel(self, channel: aiortc.RTCDataChannel): + self._log_debug("got data channel: %s", channel.label) + if channel.label == "data" and self.messaging_channel is None: + self._add_messaging_channel(channel) + self._on_after_media() + + def _on_after_media(self): + if self._number_of_incoming_media == self.expected_number_of_incoming_media: + self.incoming_media_ready_event.set() + + def _parse_incoming_streams(self, remote_sdp: str): + desc = aiortc.sdp.SessionDescription.parse(remote_sdp) + sending_medias = [m for m in desc.media if m.direction in ["sendonly", "sendrecv"]] + incoming_media_count = len(sending_medias) + if not self.should_add_data_channel: + channel_medias = [m for m in desc.media if m.kind == "application"] + incoming_media_count += len(channel_medias) + self.expected_number_of_incoming_media = incoming_media_count + + def has_incoming_video_track(self, camera_type: str) -> bool: + return camera_type in self.incoming_camera_tracks + + def has_incoming_audio_track(self) -> bool: + return len(self.incoming_audio_tracks) > 0 + + def has_messaging_channel(self) -> bool: + return self.messaging_channel is not None + + def get_incoming_video_track(self, camera_type: str, buffered: bool = False) -> aiortc.MediaStreamTrack: + assert camera_type in self.incoming_camera_tracks, "Video tracks are not enabled on this stream" + assert self.is_started, "Stream must be started" + + track = self.incoming_camera_tracks[camera_type] + relay_track = self.media_relay.subscribe(track, buffered=buffered) + return relay_track + + def get_incoming_audio_track(self, buffered: bool = False) -> aiortc.MediaStreamTrack: + assert len(self.incoming_audio_tracks) > 0, "Audio tracks are not enabled on this stream" + assert self.is_started, "Stream must be started" + + track = self.incoming_audio_tracks[0] + relay_track = self.media_relay.subscribe(track, buffered=buffered) + return relay_track + + def get_messaging_channel(self) -> aiortc.RTCDataChannel: + assert self.messaging_channel is not None, "Messaging channel is not enabled on this stream" + assert self.is_started, "Stream must be started" + + return self.messaging_channel + + def set_message_handler(self, message_handler: MessageHandler): + self.incoming_message_handlers.append(message_handler) + if self.messaging_channel is not None: + self.messaging_channel.on("message", message_handler) + + @property + def is_started(self) -> bool: + return self.peer_connection is not None and \ + self.peer_connection.localDescription is not None and \ + self.peer_connection.remoteDescription is not None and \ + self.peer_connection.connectionState != "closed" + + @property + def is_connected_and_ready(self) -> bool: + return self.peer_connection is not None and \ + self.peer_connection.connectionState == "connected" and \ + self.expected_number_of_incoming_media != 0 and self.incoming_media_ready_event.is_set() + + async def wait_for_connection(self): + assert self.is_started + await self.connection_attempted_event.wait() + if self.peer_connection.connectionState != 'connected': + raise ValueError("Connection failed.") + if self.expected_number_of_incoming_media: + await self.incoming_media_ready_event.wait() + if self.messaging_channel is not None: + await self.messaging_channel_ready_event.wait() + + async def wait_for_disconnection(self): + assert self.is_connected_and_ready + await self.connection_stopped_event.wait() + + async def stop(self): + await self.peer_connection.close() + + @abc.abstractmethod + async def start(self) -> aiortc.RTCSessionDescription: + raise NotImplementedError + + +class WebRTCOfferStream(WebRTCBaseStream): + def __init__(self, session_provider: ConnectionProvider, *args, **kwargs): + super().__init__(*args, **kwargs) + self.session_provider = session_provider + + async def start(self) -> aiortc.RTCSessionDescription: + self._add_consumer_transceivers() + if self.should_add_data_channel: + self._add_messaging_channel() + self._add_producer_tracks() + + offer = await self.peer_connection.createOffer() + await self.peer_connection.setLocalDescription(offer) + actual_offer = self.peer_connection.localDescription + + streaming_offer = StreamingOffer( + sdp=actual_offer.sdp, + video=list(self.expected_incoming_camera_types), + ) + remote_answer = await self.session_provider(streaming_offer) + self._parse_incoming_streams(remote_sdp=remote_answer.sdp) + await self.peer_connection.setRemoteDescription(remote_answer) + actual_answer = self.peer_connection.remoteDescription + + return actual_answer + + +class WebRTCAnswerStream(WebRTCBaseStream): + def __init__(self, session: aiortc.RTCSessionDescription, *args, **kwargs): + super().__init__(*args, **kwargs) + self.session = session + + def _probe_video_codecs(self) -> List[str]: + codecs = [] + for track in self.outgoing_video_tracks: + if hasattr(track, "codec_preference") and track.codec_preference() is not None: + codecs.append(track.codec_preference()) + + return codecs + + def _override_incoming_video_codecs(self, remote_sdp: str, codecs: List[str]) -> str: + desc = aiortc.sdp.SessionDescription.parse(remote_sdp) + codec_mimes = [f"video/{c}" for c in codecs] + for m in desc.media: + if m.kind != "video": + continue + + preferred_codecs: List[aiortc.RTCRtpCodecParameters] = [c for c in m.rtp.codecs if c.mimeType in codec_mimes] + if len(preferred_codecs) == 0: + raise ValueError(f"None of {preferred_codecs} codecs is supported in remote SDP") + + m.rtp.codecs = preferred_codecs + m.fmt = [c.payloadType for c in preferred_codecs] + + return str(desc) + + async def start(self) -> aiortc.RTCSessionDescription: + assert self.peer_connection.remoteDescription is None, "Connection already established" + + self._add_consumer_transceivers() + + # since we sent already encoded frames in some cases (e.g. livestream video tracks are in H264), we need to force aiortc to actually use it + # we do that by overriding supported codec information on incoming sdp + preferred_codecs = self._probe_video_codecs() + if len(preferred_codecs) > 0: + self.session.sdp = self._override_incoming_video_codecs(self.session.sdp, preferred_codecs) + + self._parse_incoming_streams(remote_sdp=self.session.sdp) + await self.peer_connection.setRemoteDescription(self.session) + + self._add_producer_tracks() + + answer = await self.peer_connection.createAnswer() + await self.peer_connection.setLocalDescription(answer) + actual_answer = self.peer_connection.localDescription + + return actual_answer diff --git a/teleoprtc/tracks.py b/teleoprtc/tracks.py new file mode 100644 index 0000000000..96d9c35249 --- /dev/null +++ b/teleoprtc/tracks.py @@ -0,0 +1,76 @@ +import asyncio +import logging +import time +import fractions +from typing import Optional, Tuple, Any + +import aiortc +from aiortc.mediastreams import VIDEO_CLOCK_RATE, VIDEO_TIME_BASE + + +def video_track_id(camera_type: str, track_id: str) -> str: + return f"{camera_type}:{track_id}" + + +def parse_video_track_id(track_id: str) -> Tuple[str, str]: + parts = track_id.split(":") + if len(parts) != 2: + raise ValueError(f"Invalid video track id: {track_id}") + + camera_type, track_id = parts + return camera_type, track_id + + +class TiciVideoStreamTrack(aiortc.MediaStreamTrack): + """ + Abstract video track which associates video track with camera_type + """ + kind = "video" + + def __init__(self, camera_type: str, dt: float, time_base: fractions.Fraction = VIDEO_TIME_BASE, clock_rate: int = VIDEO_CLOCK_RATE): + assert camera_type in ["driver", "wideRoad", "road"] + super().__init__() + # override track id to include camera type - client needs that for identification + self._id: str = video_track_id(camera_type, self._id) + self._dt: float = dt + self._time_base: fractions.Fraction = time_base + self._clock_rate: int = clock_rate + self._start: Optional[float] = None + self._logger = logging.getLogger("WebRTCStream") + + def log_debug(self, msg: Any, *args): + self._logger.debug(f"{type(self)}() {msg}", *args) + + async def next_pts(self, current_pts) -> float: + pts: float = current_pts + self._dt * self._clock_rate + + data_time = pts * self._time_base + if self._start is None: + self._start = time.time() - data_time + else: + wait_time = self._start + data_time - time.time() + await asyncio.sleep(wait_time) + + return pts + + def codec_preference(self) -> Optional[str]: + return None + + +class TiciTrackWrapper(aiortc.MediaStreamTrack): + """ + Associates video track with camera_type + """ + def __init__(self, camera_type: str, track: aiortc.MediaStreamTrack): + assert track.kind == "video" + assert not isinstance(track, TiciVideoStreamTrack) + super().__init__() + self._id = video_track_id(camera_type, track.id) + self._track = track + + @property + def kind(self) -> str: + return self._track.kind + + async def recv(self): + return await self._track.recv() diff --git a/third_party/mapbox-gl-native-qt/include/QMapbox b/third_party/mapbox-gl-native-qt/include/QMapbox deleted file mode 100644 index a8479c09aa..0000000000 --- a/third_party/mapbox-gl-native-qt/include/QMapbox +++ /dev/null @@ -1 +0,0 @@ -#include "qmapbox.hpp" diff --git a/third_party/mapbox-gl-native-qt/include/QMapboxGL b/third_party/mapbox-gl-native-qt/include/QMapboxGL deleted file mode 100644 index 15b55a9abe..0000000000 --- a/third_party/mapbox-gl-native-qt/include/QMapboxGL +++ /dev/null @@ -1 +0,0 @@ -#include "qmapboxgl.hpp" diff --git a/third_party/mapbox-gl-native-qt/include/qmapbox.hpp b/third_party/mapbox-gl-native-qt/include/qmapbox.hpp deleted file mode 100644 index 3acc9d55e0..0000000000 --- a/third_party/mapbox-gl-native-qt/include/qmapbox.hpp +++ /dev/null @@ -1,147 +0,0 @@ -#ifndef QMAPBOX_H -#define QMAPBOX_H - -#include -#include -#include -#include -#include - -// This header follows the Qt coding style: https://wiki.qt.io/Qt_Coding_Style - -#if !defined(QT_MAPBOXGL_STATIC) -# if defined(QT_BUILD_MAPBOXGL_LIB) -# define Q_MAPBOXGL_EXPORT Q_DECL_EXPORT -# else -# define Q_MAPBOXGL_EXPORT Q_DECL_IMPORT -# endif -#else -# define Q_MAPBOXGL_EXPORT -#endif - -namespace QMapbox { - -typedef QPair Coordinate; -typedef QPair CoordinateZoom; -typedef QPair ProjectedMeters; - -typedef QVector Coordinates; -typedef QVector CoordinatesCollection; - -typedef QVector CoordinatesCollections; - -struct Q_MAPBOXGL_EXPORT Feature { - enum Type { - PointType = 1, - LineStringType, - PolygonType - }; - - /*! Class constructor. */ - Feature(Type type_ = PointType, const CoordinatesCollections& geometry_ = CoordinatesCollections(), - const QVariantMap& properties_ = QVariantMap(), const QVariant& id_ = QVariant()) - : type(type_), geometry(geometry_), properties(properties_), id(id_) {} - - Type type; - CoordinatesCollections geometry; - QVariantMap properties; - QVariant id; -}; - -struct Q_MAPBOXGL_EXPORT ShapeAnnotationGeometry { - enum Type { - LineStringType = 1, - PolygonType, - MultiLineStringType, - MultiPolygonType - }; - - /*! Class constructor. */ - ShapeAnnotationGeometry(Type type_ = LineStringType, const CoordinatesCollections& geometry_ = CoordinatesCollections()) - : type(type_), geometry(geometry_) {} - - Type type; - CoordinatesCollections geometry; -}; - -struct Q_MAPBOXGL_EXPORT SymbolAnnotation { - Coordinate geometry; - QString icon; -}; - -struct Q_MAPBOXGL_EXPORT LineAnnotation { - /*! Class constructor. */ - LineAnnotation(const ShapeAnnotationGeometry& geometry_ = ShapeAnnotationGeometry(), float opacity_ = 1.0f, - float width_ = 1.0f, const QColor& color_ = Qt::black) - : geometry(geometry_), opacity(opacity_), width(width_), color(color_) {} - - ShapeAnnotationGeometry geometry; - float opacity; - float width; - QColor color; -}; - -struct Q_MAPBOXGL_EXPORT FillAnnotation { - /*! Class constructor. */ - FillAnnotation(const ShapeAnnotationGeometry& geometry_ = ShapeAnnotationGeometry(), float opacity_ = 1.0f, - const QColor& color_ = Qt::black, const QVariant& outlineColor_ = QVariant()) - : geometry(geometry_), opacity(opacity_), color(color_), outlineColor(outlineColor_) {} - - ShapeAnnotationGeometry geometry; - float opacity; - QColor color; - QVariant outlineColor; -}; - -typedef QVariant Annotation; -typedef quint32 AnnotationID; -typedef QVector AnnotationIDs; - -enum NetworkMode { - Online, // Default - Offline, -}; - -Q_MAPBOXGL_EXPORT QVector >& defaultStyles(); - -Q_MAPBOXGL_EXPORT NetworkMode networkMode(); -Q_MAPBOXGL_EXPORT void setNetworkMode(NetworkMode); - -// This struct is a 1:1 copy of mbgl::CustomLayerRenderParameters. -struct Q_MAPBOXGL_EXPORT CustomLayerRenderParameters { - double width; - double height; - double latitude; - double longitude; - double zoom; - double bearing; - double pitch; - double fieldOfView; -}; - -class Q_MAPBOXGL_EXPORT CustomLayerHostInterface { -public: - virtual ~CustomLayerHostInterface() = default; - virtual void initialize() = 0; - virtual void render(const CustomLayerRenderParameters&) = 0; - virtual void deinitialize() = 0; -}; - -Q_MAPBOXGL_EXPORT double metersPerPixelAtLatitude(double latitude, double zoom); -Q_MAPBOXGL_EXPORT ProjectedMeters projectedMetersForCoordinate(const Coordinate &); -Q_MAPBOXGL_EXPORT Coordinate coordinateForProjectedMeters(const ProjectedMeters &); - -} // namespace QMapbox - -Q_DECLARE_METATYPE(QMapbox::Coordinate); -Q_DECLARE_METATYPE(QMapbox::Coordinates); -Q_DECLARE_METATYPE(QMapbox::CoordinatesCollection); -Q_DECLARE_METATYPE(QMapbox::CoordinatesCollections); -Q_DECLARE_METATYPE(QMapbox::Feature); - -Q_DECLARE_METATYPE(QMapbox::SymbolAnnotation); -Q_DECLARE_METATYPE(QMapbox::ShapeAnnotationGeometry); -Q_DECLARE_METATYPE(QMapbox::LineAnnotation); -Q_DECLARE_METATYPE(QMapbox::FillAnnotation); - -#endif // QMAPBOX_H diff --git a/third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp b/third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp deleted file mode 100644 index 337991aa1c..0000000000 --- a/third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp +++ /dev/null @@ -1,277 +0,0 @@ -#ifndef QMAPBOXGL_H -#define QMAPBOXGL_H - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -class QMapboxGLPrivate; - -// This header follows the Qt coding style: https://wiki.qt.io/Qt_Coding_Style - -class Q_MAPBOXGL_EXPORT QMapboxGLSettings -{ -public: - QMapboxGLSettings(); - - enum GLContextMode { - UniqueGLContext = 0, - SharedGLContext - }; - - enum MapMode { - Continuous = 0, - Static - }; - - enum ConstrainMode { - NoConstrain = 0, - ConstrainHeightOnly, - ConstrainWidthAndHeight - }; - - enum ViewportMode { - DefaultViewport = 0, - FlippedYViewport - }; - - GLContextMode contextMode() const; - void setContextMode(GLContextMode); - - MapMode mapMode() const; - void setMapMode(MapMode); - - ConstrainMode constrainMode() const; - void setConstrainMode(ConstrainMode); - - ViewportMode viewportMode() const; - void setViewportMode(ViewportMode); - - unsigned cacheDatabaseMaximumSize() const; - void setCacheDatabaseMaximumSize(unsigned); - - QString cacheDatabasePath() const; - void setCacheDatabasePath(const QString &); - - QString assetPath() const; - void setAssetPath(const QString &); - - QString accessToken() const; - void setAccessToken(const QString &); - - QString apiBaseUrl() const; - void setApiBaseUrl(const QString &); - - QString localFontFamily() const; - void setLocalFontFamily(const QString &); - - std::function resourceTransform() const; - void setResourceTransform(const std::function &); - -private: - GLContextMode m_contextMode; - MapMode m_mapMode; - ConstrainMode m_constrainMode; - ViewportMode m_viewportMode; - - unsigned m_cacheMaximumSize; - QString m_cacheDatabasePath; - QString m_assetPath; - QString m_accessToken; - QString m_apiBaseUrl; - QString m_localFontFamily; - std::function m_resourceTransform; -}; - -struct Q_MAPBOXGL_EXPORT QMapboxGLCameraOptions { - QVariant center; // Coordinate - QVariant anchor; // QPointF - QVariant zoom; // double - QVariant bearing; // double - QVariant pitch; // double -}; - -class Q_MAPBOXGL_EXPORT QMapboxGL : public QObject -{ - Q_OBJECT - Q_PROPERTY(double latitude READ latitude WRITE setLatitude) - Q_PROPERTY(double longitude READ longitude WRITE setLongitude) - Q_PROPERTY(double zoom READ zoom WRITE setZoom) - Q_PROPERTY(double bearing READ bearing WRITE setBearing) - Q_PROPERTY(double pitch READ pitch WRITE setPitch) - Q_PROPERTY(QString styleJson READ styleJson WRITE setStyleJson) - Q_PROPERTY(QString styleUrl READ styleUrl WRITE setStyleUrl) - Q_PROPERTY(double scale READ scale WRITE setScale) - Q_PROPERTY(QMapbox::Coordinate coordinate READ coordinate WRITE setCoordinate) - Q_PROPERTY(QMargins margins READ margins WRITE setMargins) - -public: - enum MapChange { - MapChangeRegionWillChange = 0, - MapChangeRegionWillChangeAnimated, - MapChangeRegionIsChanging, - MapChangeRegionDidChange, - MapChangeRegionDidChangeAnimated, - MapChangeWillStartLoadingMap, - MapChangeDidFinishLoadingMap, - MapChangeDidFailLoadingMap, - MapChangeWillStartRenderingFrame, - MapChangeDidFinishRenderingFrame, - MapChangeDidFinishRenderingFrameFullyRendered, - MapChangeWillStartRenderingMap, - MapChangeDidFinishRenderingMap, - MapChangeDidFinishRenderingMapFullyRendered, - MapChangeDidFinishLoadingStyle, - MapChangeSourceDidChange - }; - - enum MapLoadingFailure { - StyleParseFailure, - StyleLoadFailure, - NotFoundFailure, - UnknownFailure - }; - - // Determines the orientation of the map. - enum NorthOrientation { - NorthUpwards, // Default - NorthRightwards, - NorthDownwards, - NorthLeftwards, - }; - - QMapboxGL(QObject* parent = 0, - const QMapboxGLSettings& = QMapboxGLSettings(), - const QSize& size = QSize(), - qreal pixelRatio = 1); - virtual ~QMapboxGL(); - - QString styleJson() const; - QString styleUrl() const; - - void setStyleJson(const QString &); - void setStyleUrl(const QString &); - - double latitude() const; - void setLatitude(double latitude); - - double longitude() const; - void setLongitude(double longitude); - - double scale() const; - void setScale(double scale, const QPointF ¢er = QPointF()); - - double zoom() const; - void setZoom(double zoom); - - double minimumZoom() const; - double maximumZoom() const; - - double bearing() const; - void setBearing(double degrees); - void setBearing(double degrees, const QPointF ¢er); - - double pitch() const; - void setPitch(double pitch); - void pitchBy(double pitch); - - NorthOrientation northOrientation() const; - void setNorthOrientation(NorthOrientation); - - QMapbox::Coordinate coordinate() const; - void setCoordinate(const QMapbox::Coordinate &); - void setCoordinateZoom(const QMapbox::Coordinate &, double zoom); - - void jumpTo(const QMapboxGLCameraOptions&); - - void setGestureInProgress(bool inProgress); - - void setTransitionOptions(qint64 duration, qint64 delay = 0); - - void addAnnotationIcon(const QString &name, const QImage &sprite); - - QMapbox::AnnotationID addAnnotation(const QMapbox::Annotation &); - void updateAnnotation(QMapbox::AnnotationID, const QMapbox::Annotation &); - void removeAnnotation(QMapbox::AnnotationID); - - bool setLayoutProperty(const QString &layer, const QString &property, const QVariant &value); - bool setPaintProperty(const QString &layer, const QString &property, const QVariant &value); - - bool isFullyLoaded() const; - - void moveBy(const QPointF &offset); - void scaleBy(double scale, const QPointF ¢er = QPointF()); - void rotateBy(const QPointF &first, const QPointF &second); - - void resize(const QSize &size); - - double metersPerPixelAtLatitude(double latitude, double zoom) const; - QMapbox::ProjectedMeters projectedMetersForCoordinate(const QMapbox::Coordinate &) const; - QMapbox::Coordinate coordinateForProjectedMeters(const QMapbox::ProjectedMeters &) const; - QPointF pixelForCoordinate(const QMapbox::Coordinate &) const; - QMapbox::Coordinate coordinateForPixel(const QPointF &) const; - - QMapbox::CoordinateZoom coordinateZoomForBounds(const QMapbox::Coordinate &sw, QMapbox::Coordinate &ne) const; - QMapbox::CoordinateZoom coordinateZoomForBounds(const QMapbox::Coordinate &sw, QMapbox::Coordinate &ne, double bearing, double pitch); - - void setMargins(const QMargins &margins); - QMargins margins() const; - - void addSource(const QString &sourceID, const QVariantMap& params); - bool sourceExists(const QString &sourceID); - void updateSource(const QString &sourceID, const QVariantMap& params); - void removeSource(const QString &sourceID); - - void addImage(const QString &name, const QImage &sprite); - void removeImage(const QString &name); - - void addCustomLayer(const QString &id, - QScopedPointer& host, - const QString& before = QString()); - void addLayer(const QVariantMap ¶ms, const QString& before = QString()); - bool layerExists(const QString &id); - void removeLayer(const QString &id); - - QVector layerIds() const; - - void setFilter(const QString &layer, const QVariant &filter); - QVariant getFilter(const QString &layer) const; - // When rendering on a different thread, - // should be called on the render thread. - void createRenderer(); - void destroyRenderer(); - void setFramebufferObject(quint32 fbo, const QSize &size); - -public slots: - void render(); - void connectionEstablished(); - - // Commit changes, load all the resources - // and renders the map when completed. - void startStaticRender(); - -signals: - void needsRendering(); - void mapChanged(QMapboxGL::MapChange); - void mapLoadingFailed(QMapboxGL::MapLoadingFailure, const QString &reason); - void copyrightsChanged(const QString ©rightsHtml); - - void staticRenderFinished(const QString &error); - -private: - Q_DISABLE_COPY(QMapboxGL) - - QMapboxGLPrivate *d_ptr; -}; - -Q_DECLARE_METATYPE(QMapboxGL::MapChange); -Q_DECLARE_METATYPE(QMapboxGL::MapLoadingFailure); - -#endif // QMAPBOXGL_H diff --git a/third_party/maplibre-native-qt/aarch64 b/third_party/maplibre-native-qt/aarch64 new file mode 120000 index 0000000000..062c65e8d9 --- /dev/null +++ b/third_party/maplibre-native-qt/aarch64 @@ -0,0 +1 @@ +larch64/ \ No newline at end of file diff --git a/third_party/maplibre-native-qt/build.sh b/third_party/maplibre-native-qt/build.sh new file mode 100755 index 0000000000..c64f0fc649 --- /dev/null +++ b/third_party/maplibre-native-qt/build.sh @@ -0,0 +1,38 @@ +#!/usr/bin/env bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" + +ARCHNAME="x86_64" +MAPLIBRE_FLAGS="-DMLN_QT_WITH_LOCATION=OFF" +if [ -f /AGNOS ]; then + ARCHNAME="larch64" + #MAPLIBRE_FLAGS="$MAPLIBRE_FLAGS -DCMAKE_SYSTEM_NAME=Android -DANDROID_ABI=arm64-v8a" +fi + +cd $DIR +if [ ! -d maplibre ]; then + git clone git@github.com:maplibre/maplibre-native-qt.git $DIR/maplibre +fi + +cd maplibre +git fetch --all +git checkout 3726266e127c1f94ad64837c9dbe03d238255816 +git submodule update --depth=1 --recursive --init + +# build +mkdir -p build +cd build +set -x +cmake $MAPLIBRE_FLAGS $DIR/maplibre +make -j$(nproc) || make -j2 || make -j1 + +INSTALL_DIR="$DIR/$ARCHNAME" +rm -rf $INSTALL_DIR +mkdir -p $INSTALL_DIR + +rm -rf $INSTALL_DIR/lib $DIR/include +mkdir -p $INSTALL_DIR/lib $INSTALL_DIR/include $DIR/include +cp -r $DIR/maplibre/build/src/core/*.so* $INSTALL_DIR/lib +cp -r $DIR/maplibre/build/src/core/include/* $INSTALL_DIR/include +cp -r $DIR/maplibre/src/**/*.hpp $DIR/include diff --git a/third_party/maplibre-native-qt/include/conversion_p.hpp b/third_party/maplibre-native-qt/include/conversion_p.hpp new file mode 100644 index 0000000000..38b03d498e --- /dev/null +++ b/third_party/maplibre-native-qt/include/conversion_p.hpp @@ -0,0 +1,241 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2018 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "geojson_p.hpp" +#include "types.hpp" + +#include +#include + +#include +#include + +#include + +namespace mbgl::style::conversion { + +std::string convertColor(const QColor &color); + +template <> +class ConversionTraits { +public: + static bool isUndefined(const QVariant &value) { return value.isNull() || !value.isValid(); } + + static bool isArray(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + return QMetaType::canConvert(value.metaType(), QMetaType(QMetaType::QVariantList)); +#else + return value.canConvert(QVariant::List); +#endif + } + + static std::size_t arrayLength(const QVariant &value) { return value.toList().size(); } + + static QVariant arrayMember(const QVariant &value, std::size_t i) { return value.toList()[static_cast(i)]; } + + static bool isObject(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + return QMetaType::canConvert(value.metaType(), QMetaType(QMetaType::QVariantMap)) || + value.typeId() == QMetaType::QByteArray +#else + return value.canConvert(QVariant::Map) || value.type() == QVariant::ByteArray +#endif + || QString(value.typeName()) == QStringLiteral("QMapLibre::Feature") || + value.userType() == qMetaTypeId>() || + value.userType() == qMetaTypeId>() || + value.userType() == qMetaTypeId>(); + } + + static std::optional objectMember(const QVariant &value, const char *key) { + auto map = value.toMap(); + auto iter = map.constFind(key); + + if (iter != map.constEnd()) { + return iter.value(); + } + + return {}; + } + + template + static std::optional eachMember(const QVariant &value, Fn &&fn) { + auto map = value.toMap(); + auto iter = map.constBegin(); + + while (iter != map.constEnd()) { + std::optional result = fn(iter.key().toStdString(), QVariant(iter.value())); + if (result) { + return result; + } + + ++iter; + } + + return {}; + } + + static std::optional toBool(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Bool) { +#else + if (value.type() == QVariant::Bool) { +#endif + return value.toBool(); + } + + return {}; + } + + static std::optional toNumber(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Int || value.typeId() == QMetaType::Double || + value.typeId() == QMetaType::Long || value.typeId() == QMetaType::LongLong || + value.typeId() == QMetaType::ULong || value.typeId() == QMetaType::ULongLong) { +#else + if (value.type() == QVariant::Int || value.type() == QVariant::Double || value.type() == QVariant::LongLong || + value.type() == QVariant::ULongLong) { +#endif + return value.toFloat(); + } + + return {}; + } + + static std::optional toDouble(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Int || value.typeId() == QMetaType::Double || + value.typeId() == QMetaType::Long || value.typeId() == QMetaType::LongLong || + value.typeId() == QMetaType::ULong || value.typeId() == QMetaType::ULongLong) { +#else + if (value.type() == QVariant::Int || value.type() == QVariant::Double || value.type() == QVariant::LongLong || + value.type() == QVariant::ULongLong) { +#endif + return value.toDouble(); + } + + return {}; + } + + static std::optional toString(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::QString) { + return value.toString().toStdString(); + } + + if (value.typeId() == QMetaType::QColor) { + return convertColor(value.value()); + } +#else + if (value.type() == QVariant::String) { + return value.toString().toStdString(); + } + + if (value.type() == QVariant::Color) { + return convertColor(value.value()); + } +#endif + return {}; + } + + static std::optional toValue(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Bool) { + return {value.toBool()}; + } + + if (value.typeId() == QMetaType::QString) { + return {value.toString().toStdString()}; + } + + if (value.typeId() == QMetaType::QColor) { + return {convertColor(value.value())}; + } + + if (value.typeId() == QMetaType::Int) { + return {static_cast(value.toInt())}; + } + + if (QMetaType::canConvert(value.metaType(), QMetaType(QMetaType::Double))) { + return {value.toDouble()}; + } +#else + if (value.type() == QVariant::Bool) { + return {value.toBool()}; + } + + if (value.type() == QVariant::String) { + return {value.toString().toStdString()}; + } + + if (value.type() == QVariant::Color) { + return {convertColor(value.value())}; + } + + if (value.type() == QVariant::Int) { + return {static_cast(value.toInt())}; + } + + if (value.canConvert(QVariant::Double)) { + return {value.toDouble()}; + } +#endif + return {}; + } + + static std::optional toGeoJSON(const QVariant &value, Error &error) { + if (value.typeName() == QStringLiteral("QMapLibre::Feature")) { + return GeoJSON{QMapLibre::GeoJSON::asFeature(value.value())}; + } + + if (value.userType() == qMetaTypeId>()) { + return featureCollectionToGeoJSON(value.value>()); + } + + if (value.userType() == qMetaTypeId>()) { + return featureCollectionToGeoJSON(value.value>()); + } + + if (value.userType() == qMetaTypeId>()) { + return featureCollectionToGeoJSON(value.value>()); + } + +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() != QMetaType::QByteArray) { +#else + if (value.type() != QVariant::ByteArray) { +#endif + error = {"JSON data must be in QByteArray"}; + return {}; + } + + const QByteArray data = value.toByteArray(); + return parseGeoJSON(std::string(data.constData(), data.size()), error); + } + +private: + template + static GeoJSON featureCollectionToGeoJSON(const T &features) { + mapbox::feature::feature_collection collection; + collection.reserve(static_cast(features.size())); + for (const auto &feature : features) { + collection.push_back(QMapLibre::GeoJSON::asFeature(feature)); + } + return GeoJSON{std::move(collection)}; + } +}; + +template +std::optional convert(const QVariant &value, Error &error, Args &&...args) { + return convert(Convertible(value), error, std::forward(args)...); +} + +inline std::string convertColor(const QColor &color) { + return QString::asprintf("rgba(%d,%d,%d,%lf)", color.red(), color.green(), color.blue(), color.alphaF()) + .toStdString(); +} + +} // namespace mbgl::style::conversion diff --git a/third_party/maplibre-native-qt/include/export_core.hpp b/third_party/maplibre-native-qt/include/export_core.hpp new file mode 100644 index 0000000000..bd5ad495db --- /dev/null +++ b/third_party/maplibre-native-qt/include/export_core.hpp @@ -0,0 +1,20 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_CORE_EXPORT_H +#define QMAPLIBRE_CORE_EXPORT_H + +#include + +#if !defined(QT_MAPLIBRE_STATIC) +#if defined(QT_BUILD_MAPLIBRE_CORE_LIB) +#define Q_MAPLIBRE_CORE_EXPORT Q_DECL_EXPORT +#else +#define Q_MAPLIBRE_CORE_EXPORT Q_DECL_IMPORT +#endif +#else +#define Q_MAPLIBRE_CORE_EXPORT +#endif + +#endif // QMAPLIBRE_CORE_EXPORT_H diff --git a/third_party/maplibre-native-qt/include/export_location.hpp b/third_party/maplibre-native-qt/include/export_location.hpp new file mode 100644 index 0000000000..a986346884 --- /dev/null +++ b/third_party/maplibre-native-qt/include/export_location.hpp @@ -0,0 +1,20 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_LOCATION_EXPORT_H +#define QMAPLIBRE_LOCATION_EXPORT_H + +#include + +#if !defined(QT_MAPLIBRE_STATIC) +#if defined(QT_BUILD_MAPLIBRE_LOCATION_LIB) +#define Q_MAPLIBRE_LOCATION_EXPORT Q_DECL_EXPORT +#else +#define Q_MAPLIBRE_LOCATION_EXPORT Q_DECL_IMPORT +#endif +#else +#define Q_MAPLIBRE_LOCATION_EXPORT +#endif + +#endif // QMAPLIBRE_LOCATION_EXPORT_H diff --git a/third_party/maplibre-native-qt/include/export_widgets.hpp b/third_party/maplibre-native-qt/include/export_widgets.hpp new file mode 100644 index 0000000000..11bc288190 --- /dev/null +++ b/third_party/maplibre-native-qt/include/export_widgets.hpp @@ -0,0 +1,20 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_WIDGETS_EXPORT_H +#define QMAPLIBRE_WIDGETS_EXPORT_H + +#include + +#if !defined(QT_MAPLIBRE_STATIC) +#if defined(QT_BUILD_MAPLIBRE_WIDGETS_LIB) +#define Q_MAPLIBRE_WIDGETS_EXPORT Q_DECL_EXPORT +#else +#define Q_MAPLIBRE_WIDGETS_EXPORT Q_DECL_IMPORT +#endif +#else +#define Q_MAPLIBRE_WIDGETS_EXPORT +#endif + +#endif // QMAPLIBRE_WIDGETS_EXPORT_H diff --git a/third_party/maplibre-native-qt/include/geojson_p.hpp b/third_party/maplibre-native-qt/include/geojson_p.hpp new file mode 100644 index 0000000000..8387f70c4b --- /dev/null +++ b/third_party/maplibre-native-qt/include/geojson_p.hpp @@ -0,0 +1,30 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "types.hpp" + +#include +#include +#include + +#include + +#include + +namespace QMapLibre::GeoJSON { + +mbgl::Point asPoint(const Coordinate &coordinate); +mbgl::MultiPoint asMultiPoint(const Coordinates &multiPoint); +mbgl::LineString asLineString(const Coordinates &lineString); +mbgl::MultiLineString asMultiLineString(const CoordinatesCollection &multiLineString); +mbgl::Polygon asPolygon(const CoordinatesCollection &polygon); +mbgl::MultiPolygon asMultiPolygon(const CoordinatesCollections &multiPolygon); +mbgl::Value asPropertyValue(const QVariant &value); +mbgl::FeatureIdentifier asFeatureIdentifier(const QVariant &id); +mbgl::GeoJSONFeature asFeature(const Feature &feature); + +} // namespace QMapLibre::GeoJSON diff --git a/third_party/maplibre-native-qt/include/gl_widget.hpp b/third_party/maplibre-native-qt/include/gl_widget.hpp new file mode 100644 index 0000000000..b2630daea7 --- /dev/null +++ b/third_party/maplibre-native-qt/include/gl_widget.hpp @@ -0,0 +1,56 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_GL_WIDGET_H +#define QMAPLIBRE_GL_WIDGET_H + +#include + +#include +#include + +#include + +#include + +QT_BEGIN_NAMESPACE + +class QKeyEvent; +class QMouseEvent; +class QWheelEvent; + +QT_END_NAMESPACE + +namespace QMapLibre { + +class GLWidgetPrivate; + +class Q_MAPLIBRE_WIDGETS_EXPORT GLWidget : public QOpenGLWidget { + Q_OBJECT + +public: + explicit GLWidget(const Settings &); + ~GLWidget() override; + + Map *map(); + +protected: + // QWidget implementation. + void mousePressEvent(QMouseEvent *event) override; + void mouseMoveEvent(QMouseEvent *event) override; + void wheelEvent(QWheelEvent *event) override; + + // Q{,Open}GLWidget implementation. + void initializeGL() override; + void paintGL() override; + +private: + Q_DISABLE_COPY(GLWidget) + + std::unique_ptr d_ptr; +}; + +} // namespace QMapLibre + +#endif // QMAPLIBRE_GL_WIDGET_H diff --git a/third_party/maplibre-native-qt/include/gl_widget_p.hpp b/third_party/maplibre-native-qt/include/gl_widget_p.hpp new file mode 100644 index 0000000000..c97781fd29 --- /dev/null +++ b/third_party/maplibre-native-qt/include/gl_widget_p.hpp @@ -0,0 +1,42 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include +#include + +#include + +QT_BEGIN_NAMESPACE + +class QKeyEvent; +class QMouseEvent; +class QWheelEvent; + +QT_END_NAMESPACE + +namespace QMapLibre { + +class GLWidgetPrivate : public QObject { + Q_OBJECT + +public: + explicit GLWidgetPrivate(QObject *parent, Settings settings); + ~GLWidgetPrivate() override; + + void handleMousePressEvent(QMouseEvent *event); + void handleMouseMoveEvent(QMouseEvent *event); + void handleWheelEvent(QWheelEvent *event) const; + + std::unique_ptr m_map{}; + Settings m_settings; + +private: + Q_DISABLE_COPY(GLWidgetPrivate); + + QPointF m_lastPos; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/map.hpp b/third_party/maplibre-native-qt/include/map.hpp new file mode 100644 index 0000000000..cd56996185 --- /dev/null +++ b/third_party/maplibre-native-qt/include/map.hpp @@ -0,0 +1,205 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_MAP_H +#define QMAPLIBRE_MAP_H + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace QMapLibre { + +class MapPrivate; + +class Q_MAPLIBRE_CORE_EXPORT Map : public QObject { + Q_OBJECT + Q_PROPERTY(double latitude READ latitude WRITE setLatitude) + Q_PROPERTY(double longitude READ longitude WRITE setLongitude) + Q_PROPERTY(double zoom READ zoom WRITE setZoom) + Q_PROPERTY(double bearing READ bearing WRITE setBearing) + Q_PROPERTY(double pitch READ pitch WRITE setPitch) + Q_PROPERTY(QString styleJson READ styleJson WRITE setStyleJson) + Q_PROPERTY(QString styleUrl READ styleUrl WRITE setStyleUrl) + Q_PROPERTY(double scale READ scale WRITE setScale) + Q_PROPERTY(QMapLibre::Coordinate coordinate READ coordinate WRITE setCoordinate) + Q_PROPERTY(QMargins margins READ margins WRITE setMargins) + +public: + enum MapChange { + MapChangeRegionWillChange = 0, + MapChangeRegionWillChangeAnimated, + MapChangeRegionIsChanging, + MapChangeRegionDidChange, + MapChangeRegionDidChangeAnimated, + MapChangeWillStartLoadingMap, + MapChangeDidFinishLoadingMap, + MapChangeDidFailLoadingMap, + MapChangeWillStartRenderingFrame, + MapChangeDidFinishRenderingFrame, + MapChangeDidFinishRenderingFrameFullyRendered, + MapChangeWillStartRenderingMap, + MapChangeDidFinishRenderingMap, + MapChangeDidFinishRenderingMapFullyRendered, + MapChangeDidFinishLoadingStyle, + MapChangeSourceDidChange + }; + + enum MapLoadingFailure { + StyleParseFailure, + StyleLoadFailure, + NotFoundFailure, + UnknownFailure + }; + + // Determines the orientation of the map. + enum NorthOrientation { + NorthUpwards, // Default + NorthRightwards, + NorthDownwards, + NorthLeftwards, + }; + + explicit Map(QObject *parent = nullptr, + const Settings &settings = Settings(), + const QSize &size = QSize(), + qreal pixelRatio = 1); + ~Map() override; + + [[nodiscard]] QString styleJson() const; + [[nodiscard]] QString styleUrl() const; + + void setStyleJson(const QString &); + void setStyleUrl(const QString &); + + [[nodiscard]] double latitude() const; + void setLatitude(double latitude); + + [[nodiscard]] double longitude() const; + void setLongitude(double longitude); + + [[nodiscard]] double scale() const; + void setScale(double scale, const QPointF ¢er = QPointF()); + + [[nodiscard]] double zoom() const; + void setZoom(double zoom); + + [[nodiscard]] double minimumZoom() const; + [[nodiscard]] double maximumZoom() const; + + [[nodiscard]] double bearing() const; + void setBearing(double degrees); + void setBearing(double degrees, const QPointF ¢er); + + [[nodiscard]] double pitch() const; + void setPitch(double pitch); + void pitchBy(double pitch); + + [[nodiscard]] NorthOrientation northOrientation() const; + void setNorthOrientation(NorthOrientation); + + [[nodiscard]] Coordinate coordinate() const; + void setCoordinate(const Coordinate &coordinate); + void setCoordinateZoom(const Coordinate &coordinate, double zoom); + + void jumpTo(const CameraOptions &); + + void setGestureInProgress(bool inProgress); + + void setTransitionOptions(qint64 duration, qint64 delay = 0); + + void addAnnotationIcon(const QString &name, const QImage &sprite); + + AnnotationID addAnnotation(const Annotation &annotation); + void updateAnnotation(AnnotationID id, const Annotation &annotation); + void removeAnnotation(AnnotationID id); + + bool setLayoutProperty(const QString &layerId, const QString &propertyName, const QVariant &value); + bool setPaintProperty(const QString &layerId, const QString &propertyName, const QVariant &value); + + [[nodiscard]] bool isFullyLoaded() const; + + void moveBy(const QPointF &offset); + void scaleBy(double scale, const QPointF ¢er = QPointF()); + void rotateBy(const QPointF &first, const QPointF &second); + + void resize(const QSize &size); + + [[nodiscard]] QPointF pixelForCoordinate(const Coordinate &coordinate) const; + [[nodiscard]] Coordinate coordinateForPixel(const QPointF &pixel) const; + + [[nodiscard]] CoordinateZoom coordinateZoomForBounds(const Coordinate &sw, const Coordinate &ne) const; + [[nodiscard]] CoordinateZoom coordinateZoomForBounds(const Coordinate &sw, + const Coordinate &ne, + double bearing, + double pitch); + + void setMargins(const QMargins &margins); + [[nodiscard]] QMargins margins() const; + + void addSource(const QString &id, const QVariantMap ¶ms); + bool sourceExists(const QString &id); + void updateSource(const QString &id, const QVariantMap ¶ms); + void removeSource(const QString &id); + + void addImage(const QString &id, const QImage &sprite); + void removeImage(const QString &id); + + void addCustomLayer(const QString &id, + std::unique_ptr host, + const QString &before = QString()); + void addLayer(const QString &id, const QVariantMap ¶ms, const QString &before = QString()); + bool layerExists(const QString &id); + void removeLayer(const QString &id); + + [[nodiscard]] QVector layerIds() const; + + void setFilter(const QString &layerId, const QVariant &filter); + [[nodiscard]] QVariant getFilter(const QString &layerId) const; + // When rendering on a different thread, + // should be called on the render thread. + void createRenderer(); + void destroyRenderer(); + void setFramebufferObject(quint32 fbo, const QSize &size); + +public slots: + void render(); + void setConnectionEstablished(); + + // Commit changes, load all the resources + // and renders the map when completed. + void startStaticRender(); + +signals: + void needsRendering(); + void mapChanged(Map::MapChange); + void mapLoadingFailed(Map::MapLoadingFailure, const QString &reason); + void copyrightsChanged(const QString ©rightsHtml); + + void staticRenderFinished(const QString &error); + +private: + Q_DISABLE_COPY(Map) + + std::unique_ptr d_ptr; +}; + +} // namespace QMapLibre + +Q_DECLARE_METATYPE(QMapLibre::Map::MapChange); +Q_DECLARE_METATYPE(QMapLibre::Map::MapLoadingFailure); + +#endif // QMAPLIBRE_MAP_H diff --git a/third_party/maplibre-native-qt/include/map_observer_p.hpp b/third_party/maplibre-native-qt/include/map_observer_p.hpp new file mode 100644 index 0000000000..e68c72b17b --- /dev/null +++ b/third_party/maplibre-native-qt/include/map_observer_p.hpp @@ -0,0 +1,54 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "map.hpp" + +#include +#include + +#include + +#include +#include + +namespace QMapLibre { + +class MapPrivate; + +class MapObserver : public QObject, public mbgl::MapObserver { + Q_OBJECT + +public: + explicit MapObserver(MapPrivate *ptr); + ~MapObserver() override; + + // mbgl::MapObserver implementation. + void onCameraWillChange(mbgl::MapObserver::CameraChangeMode mode) final; + void onCameraIsChanging() final; + void onCameraDidChange(mbgl::MapObserver::CameraChangeMode mode) final; + void onWillStartLoadingMap() final; + void onDidFinishLoadingMap() final; + void onDidFailLoadingMap(mbgl::MapLoadError error, const std::string &what) final; + void onWillStartRenderingFrame() final; + void onDidFinishRenderingFrame(mbgl::MapObserver::RenderFrameStatus status) final; + void onWillStartRenderingMap() final; + void onDidFinishRenderingMap(mbgl::MapObserver::RenderMode mode) final; + void onDidFinishLoadingStyle() final; + void onSourceChanged(mbgl::style::Source &source) final; + +signals: + void mapChanged(Map::MapChange); + void mapLoadingFailed(Map::MapLoadingFailure, const QString &reason); + void copyrightsChanged(const QString ©rightsHtml); + +private: + Q_DISABLE_COPY(MapObserver) + + MapPrivate *d_ptrRef; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/map_p.hpp b/third_party/maplibre-native-qt/include/map_p.hpp new file mode 100644 index 0000000000..9ca0c7e6f5 --- /dev/null +++ b/third_party/maplibre-native-qt/include/map_p.hpp @@ -0,0 +1,79 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "map.hpp" +#include "map_observer_p.hpp" +#include "map_renderer_p.hpp" + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +namespace QMapLibre { + +class MapPrivate : public QObject, public mbgl::RendererFrontend { + Q_OBJECT + +public: + explicit MapPrivate(Map *map, const Settings &settings, const QSize &size, qreal pixelRatio); + ~MapPrivate() override; + + // mbgl::RendererFrontend implementation. + void reset() final {} + void setObserver(mbgl::RendererObserver &observer) final; + void update(std::shared_ptr parameters) final; + + // These need to be called on the same thread. + void createRenderer(); + void destroyRenderer(); + void render(); + void setFramebufferObject(quint32 fbo, const QSize &size); + + using PropertySetter = std::optional (mbgl::style::Layer::*)( + const std::string &, const mbgl::style::conversion::Convertible &); + [[nodiscard]] bool setProperty(const PropertySetter &setter, + const QString &layerId, + const QString &name, + const QVariant &value) const; + + mbgl::EdgeInsets margins; + std::unique_ptr mapObj{}; + +public slots: + void requestRendering(); + +signals: + void needsRendering(); + +private: + Q_DISABLE_COPY(MapPrivate) + + std::recursive_mutex m_mapRendererMutex; + std::shared_ptr m_rendererObserver{}; + std::shared_ptr m_updateParameters{}; + + std::unique_ptr m_mapObserver{}; + std::unique_ptr m_mapRenderer{}; + std::unique_ptr> m_resourceTransform{}; + + Settings::GLContextMode m_mode; + qreal m_pixelRatio; + + QString m_localFontFamily; + + std::atomic_flag m_renderQueued = ATOMIC_FLAG_INIT; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/map_renderer_p.hpp b/third_party/maplibre-native-qt/include/map_renderer_p.hpp new file mode 100644 index 0000000000..b9a087c392 --- /dev/null +++ b/third_party/maplibre-native-qt/include/map_renderer_p.hpp @@ -0,0 +1,63 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "settings.hpp" + +#include "utils/renderer_backend.hpp" + +#include +#include +#include + +#include + +#include + +#include +#include + +namespace mbgl { +class Renderer; +class UpdateParameters; +} // namespace mbgl + +namespace QMapLibre { + +class RendererBackend; + +class MapRenderer : public QObject { + Q_OBJECT + +public: + MapRenderer(qreal pixelRatio, Settings::GLContextMode, const QString &localFontFamily); + ~MapRenderer() override; + + void render(); + void updateFramebuffer(quint32 fbo, const mbgl::Size &size); + void setObserver(mbgl::RendererObserver *observer); + + // Thread-safe, called by the Frontend + void updateParameters(std::shared_ptr parameters); + +signals: + void needsRendering(); + +private: + MBGL_STORE_THREAD(tid) + + Q_DISABLE_COPY(MapRenderer) + + std::mutex m_updateMutex; + std::shared_ptr m_updateParameters; + + RendererBackend m_backend; + std::unique_ptr m_renderer{}; + + bool m_forceScheduler{}; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/qgeomap.hpp b/third_party/maplibre-native-qt/include/qgeomap.hpp new file mode 100644 index 0000000000..5eb0180503 --- /dev/null +++ b/third_party/maplibre-native-qt/include/qgeomap.hpp @@ -0,0 +1,54 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "export_location.hpp" + +#include +#include + +#include + +namespace QMapLibre { + +class QGeoMapMapLibrePrivate; + +class Q_MAPLIBRE_LOCATION_EXPORT QGeoMapMapLibre : public QGeoMap { + Q_OBJECT + Q_DECLARE_PRIVATE(QGeoMapMapLibre) + +public: + explicit QGeoMapMapLibre(QGeoMappingManagerEngine *engine, QObject *parent = nullptr); + ~QGeoMapMapLibre() override; + + [[nodiscard]] Capabilities capabilities() const override; + + void setSettings(const Settings &settings); + void setMapItemsBefore(const QString &mapItemsBefore); + + void addStyleParameter(StyleParameter *parameter); + void removeStyleParameter(StyleParameter *parameter); + void clearStyleParameters(); + +private Q_SLOTS: + // QMapLibre + void onMapChanged(Map::MapChange); + + // QDeclarativeGeoMapItemBase + void onMapItemPropertyChanged(); + void onMapItemSubPropertyChanged(); + void onMapItemUnsupportedPropertyChanged(); + void onMapItemGeometryChanged(); + + // StyleParameter + void onStyleParameterUpdated(StyleParameter *parameter); + +private: + QSGNode *updateSceneGraph(QSGNode *oldNode, QQuickWindow *window) override; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/qgeomap_p.hpp b/third_party/maplibre-native-qt/include/qgeomap_p.hpp new file mode 100644 index 0000000000..ce415d9bcf --- /dev/null +++ b/third_party/maplibre-native-qt/include/qgeomap_p.hpp @@ -0,0 +1,93 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "qgeomap.hpp" + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace QMapLibre { + +class Map; +class StyleChange; + +class QGeoMapMapLibrePrivate : public QGeoMapPrivate { + Q_DECLARE_PUBLIC(QGeoMapMapLibre) + +public: + explicit QGeoMapMapLibrePrivate(QGeoMappingManagerEngine *engine); + ~QGeoMapMapLibrePrivate() override; + + QSGNode *updateSceneGraph(QSGNode *oldNode, QQuickWindow *window); + + QGeoMap::ItemTypes supportedMapItemTypes() const override; + void addMapItem(QDeclarativeGeoMapItemBase *item) override; + void removeMapItem(QDeclarativeGeoMapItemBase *item) override; + + void addStyleParameter(StyleParameter *parameter); + void removeStyleParameter(StyleParameter *parameter); + void clearStyleParameters(); + + /* Data members */ + enum SyncState : int { + NoSync = 0, + ViewportSync = 1 << 0, + CameraDataSync = 1 << 1, + MapTypeSync = 1 << 2, + VisibleAreaSync = 1 << 3 + }; + Q_DECLARE_FLAGS(SyncStates, SyncState); + + Settings m_settings; + QString m_mapItemsBefore; + + QList m_mapParameters; + + QTimer m_refresh; + bool m_shouldRefresh = true; + bool m_warned = false; + bool m_threadedRendering = false; + bool m_styleLoaded = false; + + SyncStates m_syncState = NoSync; + + std::vector> m_styleChanges; + +protected: + void changeViewportSize(const QSize &size) override; + void changeCameraData(const QGeoCameraData &data) override; +#if QT_VERSION >= QT_VERSION_CHECK(6, 5, 0) + void changeActiveMapType(const QGeoMapType &mapType) override; +#else + void changeActiveMapType(const QGeoMapType mapType) override; +#endif + + void setVisibleArea(const QRectF &visibleArea) override; + QRectF visibleArea() const override; + +private: + Q_DISABLE_COPY(QGeoMapMapLibrePrivate); + + void syncStyleChanges(Map *map); + void threadedRenderingHack(QQuickWindow *window, Map *map); + + QRectF m_visibleArea; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS(QGeoMapMapLibrePrivate::SyncStates) + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/qmaplibre.hpp b/third_party/maplibre-native-qt/include/qmaplibre.hpp new file mode 100644 index 0000000000..a8dc445e2b --- /dev/null +++ b/third_party/maplibre-native-qt/include/qmaplibre.hpp @@ -0,0 +1,9 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#include "export_core.hpp" +#include "map.hpp" +#include "settings.hpp" +#include "types.hpp" +#include "utils.hpp" diff --git a/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp b/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp new file mode 100644 index 0000000000..ebe9a8eea4 --- /dev/null +++ b/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp @@ -0,0 +1,6 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#include "export_widgets.hpp" +#include "gl_widget.hpp" diff --git a/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp b/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp new file mode 100644 index 0000000000..67cb4b56ce --- /dev/null +++ b/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp @@ -0,0 +1,31 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "export_location.hpp" + +#include + +#include +#include + +namespace QMapLibre { + +class Q_MAPLIBRE_LOCATION_EXPORT QtMappingEngine : public QGeoMappingManagerEngine { + Q_OBJECT + +public: + QtMappingEngine(const QVariantMap ¶meters, QGeoServiceProvider::Error *error, QString *errorString); + + QGeoMap *createMap() override; + +private: + Settings m_settings; + QString m_mapItemsBefore; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/settings.hpp b/third_party/maplibre-native-qt/include/settings.hpp new file mode 100644 index 0000000000..d6f88b871b --- /dev/null +++ b/third_party/maplibre-native-qt/include/settings.hpp @@ -0,0 +1,125 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_SETTINGS_H +#define QMAPLIBRE_SETTINGS_H + +#include +#include + +#include +#include + +#include +#include + +// TODO: this will be wrapped at some point +namespace mbgl { +class TileServerOptions; +} // namespace mbgl + +namespace QMapLibre { + +class SettingsPrivate; + +class Q_MAPLIBRE_CORE_EXPORT Settings { +public: + enum GLContextMode : bool { + UniqueGLContext, + SharedGLContext + }; + + enum MapMode { + Continuous = 0, + Static + }; + + enum ConstrainMode { + NoConstrain = 0, + ConstrainHeightOnly, + ConstrainWidthAndHeight + }; + + enum ViewportMode { + DefaultViewport = 0, + FlippedYViewport + }; + + enum ProviderTemplate { + NoProvider = 0, + MapLibreProvider, + MapTilerProvider, + MapboxProvider + }; + + using ResourceTransformFunction = std::function; + + explicit Settings(ProviderTemplate provider = NoProvider); + ~Settings(); + Settings(const Settings &s); + Settings(Settings &&s) noexcept; + Settings &operator=(const Settings &s); + Settings &operator=(Settings &&s) noexcept; + + [[nodiscard]] GLContextMode contextMode() const; + void setContextMode(GLContextMode); + + [[nodiscard]] MapMode mapMode() const; + void setMapMode(MapMode); + + [[nodiscard]] ConstrainMode constrainMode() const; + void setConstrainMode(ConstrainMode); + + [[nodiscard]] ViewportMode viewportMode() const; + void setViewportMode(ViewportMode); + + [[nodiscard]] unsigned cacheDatabaseMaximumSize() const; + void setCacheDatabaseMaximumSize(unsigned); + + [[nodiscard]] QString cacheDatabasePath() const; + void setCacheDatabasePath(const QString &path); + + [[nodiscard]] QString assetPath() const; + void setAssetPath(const QString &path); + + [[nodiscard]] QString apiKey() const; + void setApiKey(const QString &key); + + [[nodiscard]] QString apiBaseUrl() const; + void setApiBaseUrl(const QString &url); + + [[nodiscard]] QString localFontFamily() const; + void setLocalFontFamily(const QString &family); + + [[nodiscard]] QString clientName() const; + void setClientName(const QString &name); + + [[nodiscard]] QString clientVersion() const; + void setClientVersion(const QString &version); + + [[nodiscard]] ResourceTransformFunction resourceTransform() const; + void setResourceTransform(const ResourceTransformFunction &transform); + + void setProviderTemplate(ProviderTemplate providerTemplate); + void setStyles(const Styles &styles); + + [[nodiscard]] const Styles &styles() const; + [[nodiscard]] Styles providerStyles() const; + + [[nodiscard]] Coordinate defaultCoordinate() const; + void setDefaultCoordinate(const Coordinate &coordinate); + [[nodiscard]] double defaultZoom() const; + void setDefaultZoom(double zoom); + + [[nodiscard]] bool customTileServerOptions() const; + [[nodiscard]] const mbgl::TileServerOptions &tileServerOptions() const; + +private: + std::unique_ptr d_ptr; +}; + +} // namespace QMapLibre + +#endif // QMAPLIBRE_SETTINGS_H diff --git a/third_party/maplibre-native-qt/include/settings_p.hpp b/third_party/maplibre-native-qt/include/settings_p.hpp new file mode 100644 index 0000000000..257bdfd5a9 --- /dev/null +++ b/third_party/maplibre-native-qt/include/settings_p.hpp @@ -0,0 +1,57 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "settings.hpp" +#include "types.hpp" + +#include + +#include +#include + +#include +#include + +namespace mbgl { +class TileServerOptions; +} // namespace mbgl + +namespace QMapLibre { + +class SettingsPrivate { +public: + SettingsPrivate(); + + void setProviderTemplate(Settings::ProviderTemplate providerTemplate); + void setProviderApiBaseUrl(const QString &url); + + Settings::GLContextMode m_contextMode{Settings::SharedGLContext}; + Settings::MapMode m_mapMode{Settings::Continuous}; + Settings::ConstrainMode m_constrainMode{Settings::ConstrainHeightOnly}; + Settings::ViewportMode m_viewportMode{Settings::DefaultViewport}; + Settings::ProviderTemplate m_providerTemplate{Settings::NoProvider}; + + unsigned m_cacheMaximumSize; + QString m_cacheDatabasePath; + QString m_assetPath; + QString m_apiKey; + QString m_localFontFamily; + QString m_clientName; + QString m_clientVersion; + + Coordinate m_defaultCoordinate{}; + double m_defaultZoom{}; + + Styles m_styles; + + std::function m_resourceTransform; + + bool m_customTileServerOptions{}; + mbgl::TileServerOptions m_tileServerOptions{}; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/style_change_utils_p.hpp b/third_party/maplibre-native-qt/include/style_change_utils_p.hpp new file mode 100644 index 0000000000..991bb4077e --- /dev/null +++ b/third_party/maplibre-native-qt/include/style_change_utils_p.hpp @@ -0,0 +1,34 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include + +#include +#include +#include +#include +#include + +namespace QMapLibre::StyleChangeUtils { + +Feature featureFromMapRectangle(QDeclarativeRectangleMapItem *item); +Feature featureFromMapCircle(QDeclarativeCircleMapItem *item); +Feature featureFromMapPolygon(QDeclarativePolygonMapItem *item); +Feature featureFromMapPolyline(QDeclarativePolylineMapItem *item); +Feature featureFromMapItem(QDeclarativeGeoMapItemBase *item); + +QString featureId(QDeclarativeGeoMapItemBase *item); +std::vector featureLayoutPropertiesFromMapPolyline(QDeclarativePolylineMapItem *item); +std::vector featureLayoutPropertiesFromMapItem(QDeclarativeGeoMapItemBase *item); +std::vector featurePaintPropertiesFromMapRectangle(QDeclarativeRectangleMapItem *item); +std::vector featurePaingPropertiesFromMapCircle(QDeclarativeCircleMapItem *item); +std::vector featurePaintPropertiesFromMapPolygon(QDeclarativePolygonMapItem *item); +std::vector featurePaintPropertiesFromMapPolyline(QDeclarativePolylineMapItem *item); +std::vector featurePaintPropertiesFromMapItem(QDeclarativeGeoMapItemBase *item); +std::vector featurePropertiesFromMapItem(QDeclarativeGeoMapItemBase *item); + +} // namespace QMapLibre::StyleChangeUtils diff --git a/third_party/maplibre-native-qt/include/texture_node.hpp b/third_party/maplibre-native-qt/include/texture_node.hpp new file mode 100644 index 0000000000..96f63b3534 --- /dev/null +++ b/third_party/maplibre-native-qt/include/texture_node.hpp @@ -0,0 +1,42 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include +#include +#include +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) +#include +#else +#include +#endif + +#include + +namespace QMapLibre { + +class QGeoMapMapLibre; + +class TextureNode : public QSGSimpleTextureNode { +public: + TextureNode(const Settings &setting, const QSize &size, qreal pixelRatio, QGeoMapMapLibre *geoMap); + + [[nodiscard]] Map *map() const; + +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + void resize(const QSize &size, qreal pixelRatio, QQuickWindow *window); +#else + void resize(const QSize &size, qreal pixelRatio); +#endif + void render(QQuickWindow *); + +private: + std::unique_ptr m_map{}; + std::unique_ptr m_fbo{}; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/types.hpp b/third_party/maplibre-native-qt/include/types.hpp new file mode 100644 index 0000000000..696fab1a88 --- /dev/null +++ b/third_party/maplibre-native-qt/include/types.hpp @@ -0,0 +1,206 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_TYPES_H +#define QMAPLIBRE_TYPES_H + +#include + +#include +#include +#include +#include +#include +#include + +namespace QMapLibre { + +using Coordinate = QPair; +using CoordinateZoom = QPair; +using ProjectedMeters = QPair; + +using Coordinates = QVector; +using CoordinatesCollection = QVector; + +using CoordinatesCollections = QVector; + +struct Q_MAPLIBRE_CORE_EXPORT Style { + enum Type { // Taken from Qt to be in sync with QtLocation + NoMap = 0, + StreetMap, + SatelliteMapDay, + SatelliteMapNight, + TerrainMap, + HybridMap, + TransitMap, + GrayStreetMap, + PedestrianMap, + CarNavigationMap, + CycleMap, + CustomMap = 100 + }; + +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + explicit Style(QString url_, QString name_ = QString()) + : url(std::move(url_)), + name(std::move(name_)) {} +#else + explicit Style(QString url_ = QString(), QString name_ = QString()) + : url(std::move(url_)), + name(std::move(name_)) {} +#endif + + QString url; + QString name; + QString description; + bool night{}; + Type type{CustomMap}; +}; + +using Styles = QVector